Skip to content

Commit

Permalink
Mavlink: Fill in thrust field correctly for offboard rates setpoints …
Browse files Browse the repository at this point in the history
…on fixed wing (#12311)

* Fill in thrust field for rates sp
  • Loading branch information
Jaeyoung-Lim authored and dagar committed Jun 20, 2019
1 parent 4831a4b commit 4c4bcc5
Showing 1 changed file with 21 additions and 1 deletion.
22 changes: 21 additions & 1 deletion src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1419,7 +1419,27 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
}

if (!_offboard_control_mode.ignore_thrust) { // dont't overwrite thrust if it's invalid
rates_sp.thrust_body[2] = -set_attitude_target.thrust;
switch (_mavlink->get_system_type()) {
case MAV_TYPE_GENERIC:
break;

case MAV_TYPE_FIXED_WING:
rates_sp.thrust_body[0] = set_attitude_target.thrust;
break;

case MAV_TYPE_QUADROTOR:
case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
case MAV_TYPE_HELICOPTER:
rates_sp.thrust_body[2] = -set_attitude_target.thrust;
break;

case MAV_TYPE_GROUND_ROVER:
rates_sp.thrust_body[0] = set_attitude_target.thrust;
break;
}

}

if (_rates_sp_pub == nullptr) {
Expand Down

0 comments on commit 4c4bcc5

Please sign in to comment.