forked from Archive/PX4-Autopilot
mc pos ctrl: do not publish att sp in offboard && no position/velocity control
This commit is contained in:
parent
f10bcb0377
commit
0dec33526b
|
@ -1391,12 +1391,19 @@ MulticopterPositionControl::task_main()
|
|||
reset_yaw_sp = true;
|
||||
}
|
||||
|
||||
// publish attitude setpoint
|
||||
if (_att_sp_pub > 0) {
|
||||
orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_att_sp);
|
||||
/* 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);
|
||||
} 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 */
|
||||
|
|
Loading…
Reference in New Issue