mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 20:27:34 +08:00
mavlink: ATTITUDE_TARGET thrust use thrust_body magnitude
- vehicle_attitude_setpoint thrust_body is a vector, but mavlink ATTITUDE_TARGET thrust is only a magnitude - this allows the stream to be correct for both MC & FW use cases
This commit is contained in:
@@ -100,7 +100,7 @@ protected:
|
||||
msg.body_pitch_rate = att_rates_sp.pitch;
|
||||
msg.body_yaw_rate = att_rates_sp.yaw;
|
||||
|
||||
msg.thrust = att_sp.thrust_body[0];
|
||||
msg.thrust = Vector3f(att_sp.thrust_body).norm();
|
||||
|
||||
mavlink_msg_attitude_target_send_struct(_mavlink->get_channel(), &msg);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user