mc pos ctrl: do not publish att sp in offboard && no position/velocity control

This commit is contained in:
Thomas Gubler 2015-03-01 12:33:27 +01:00
parent f10bcb0377
commit 0dec33526b
1 changed files with 16 additions and 9 deletions

View File

@ -1391,13 +1391,20 @@ MulticopterPositionControl::task_main()
reset_yaw_sp = true;
}
// publish attitude setpoint
/* publish attitude setpoint
* Do not publish if offboard is enabled but position/velocity control is disabled,
* in this case the attitude setpoint is published by the mavlink app
*/
if (!(_control_mode.flag_control_offboard_enabled &&
!(_control_mode.flag_control_position_enabled ||
_control_mode.flag_control_velocity_enabled))) {
if (_att_sp_pub > 0) {
orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_att_sp);
} else {
_att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_att_sp);
}
}
/* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */
reset_int_z_manual = _control_mode.flag_armed && _control_mode.flag_control_manual_enabled && !_control_mode.flag_control_climb_rate_enabled;