mavlink / mavros

MAVLink to ROS gateway with proxy for Ground Control Station
Other
902 stars 993 forks source link

SetpointAttitude plugin can not control throttle and attitude together #285

Closed dvorak0 closed 9 years ago

dvorak0 commented 9 years ago

I am using setpoint_attitude to control my quadrotor through mavros and pixhawk.

First, I tried to control attitude and throttle at the same time by publishing geometry_msgs::PoseStamped and std_msgs::Float64. This results that the speed of rotors jumps between normal speed and arming speed. It seems the throttle is set to 0 sometimes.

I fixed the problem by using geometry_msgs::PoseStamped.pose.position.z for throttle and changed the mask (ignore_all_except_q) from (1 << 6) | (7 << 0) to (7 << 0). It works well finally.

Could anyone give me some explanations? Or it is a bug possibly.

vooon commented 9 years ago

@mhkabir any ideas?

dvorak0 commented 9 years ago

@vooon I got some ideas. The reason is removing 'static' incorrectly in https://github.com/PX4/Firmware/commit/1d283bf3c15b79ad2aa23ed3e2de7ff80f0261fe

It disabled the ability of setpoint_attititude to control thrust and attitude separately.

I've submited a pull request. https://github.com/PX4/Firmware/pull/2112.