Closed RamArvinth closed 8 years ago
~rc/override
give you ability to replace Radio Control Inputs, not output PWM.
What you need is actuator_control, but it uses scaled values and require mixer configuration, and i do not know about current support status. But initially that was done for PX4-based ground rover.
Another way is SET_SERVO command, but it is slow.
Hello @vooon , Thank you so much for your reply.
Actually, I already tried using 'actuator_control' topic and using that I was able to command desired Roll, Pitch, Yaw and Throttle values, directly. However, what I'm hoping to achieve is to have direct control over the PWM (or RPM) values commanded by my controller that I can directly pass over to the EScs (connected to pixhawk) through mavros, instead of commanding the attitude angles (Roll, Pitch, etc.)..
I'm looking to find specific mavlink msg type or mavros topics to which I could publish the commands (PWM or RPM values) in order to directly access the output pins of the pixhawk, which in a way would facilitate the bypassing of pixhawk's low level controller.
And what exactly do you mean by 'it uses scaled values and require mixer configuration'? In order to make /mavros/rc/OverRide topic work, I defined a mixer configuration which lets manual passthrough of the inputs. The mixer file I used looks like this,
Passthrough mixer for PX4IO This file defines passthrough mixers suitable for testing.
Channel group 0, channels 0-7 are passed directly through to the outputs.
M: 1
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 1 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 2 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 4 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 7 10000 10000 0 -10000 10000
I hope I was clear enough in explaining what exactly I am trying to achieve. I really appreciate all your help and guidance.
Thanks and Regards, Ram
Are you sure that you send this message: mavros_msgs/ActuatorControl?
Because it set mixer values directly, not attitude. Actual scaling was done by mixer file, by default you get ±1.0 to 1000…2000 usec.
https://github.com/PX4/Firmware/blob/master/src/modules/mavlink/mavlink_receiver.cpp#L881-L951 - seems current implementation can use only group_mix=0
.
Hi Ram,
How are you using 'actuator_control' topic to command the desired Roll, Pitch, Yaw and Throttle values, directly? Can you upload a short publisher example?
Thanks, Yoni.
Dear Developers,
We have an stationary experimental setup that consists of a beam rod whose centre is held by a base column. The joint is designed such that the rod has a 2 DOF. At each end of this rod is a motor, with only one end motor having vectoring capability by means of a servo controlled motor base mount. A platform at the centre of the rod holds the Pixhawk and other sensors.
The firmware had been cloned from the Px4/Firmware repository (https://github.com/PX4/Firmware.git). Based on the experimental setup configuration, appropriate mixers were created. The modified firmware works fine in terms of behaviour in Roll and Yaw with direct controls from the RC proving appropriate mixers are being used. Next, with this being stationary setup, by using 'mavros' we were able to achieve OFFBOARD control and perform trajectory tracking by publishing on the topic "/mavros/setpoint_attitude/attitude" and "/mavros/setpoint_attitude/att_throttle".
Objectives:
Right now, what we are doing with OFFBOARD mode is commanding varies attitudes (roll and yaw) and Pixhawk follows it using its on-board low level controller. That means the controller for now is running on pixhawk. What we want to achieve is to be able to run controller on our PC so that at the end we can control our setup using different control algorithms. Our aim in the closed loop control is to directly get PWM (or RPM) values from our controller and forward these values to each motor via output pins of pixhawk. That is, we would like to find out a way to bypass pixhawks low level controller so that the ESCs instead of taking Pixhawk commands, take our command directly.
Problems:
In order to achieve this, I have gone through all the topics of mavros package and think "/mavros/RC/OverRide" to be the moist relevant but I'm still not sure of how to make use of it. Also I could not find any example for this particular topic so that I can use it for my purpose.
Please, do suggest me if there is any other way this could be achieved if not by the above method.
To Summarize - I want to bypass the pixhawk low level controller and be able to command the motors from the controller on my system using mavros.
I apologize if this issue is not relevant here, but I am not able to find answers anywhere and I could really use your help.
Thanks!!