mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-06 16:49:51 +08:00
let vtol attitude control module publish attitude setpoint during transition
Conflicts: src/modules/commander/commander.cpp src/modules/fw_att_control/fw_att_control_main.cpp src/modules/mc_pos_control/mc_pos_control_main.cpp
This commit is contained in:
@@ -1599,7 +1599,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
orb_copy(ORB_ID(vtol_vehicle_status), vtol_vehicle_status_sub, &vtol_status);
|
||||
status.vtol_fw_permanent_stab = vtol_status.fw_permanent_stab;
|
||||
|
||||
/* Make sure that this is only adjusted if vehicle really is of type vtol*/
|
||||
/* Make sure that this is only adjusted if vehicle really is of type vtol */
|
||||
if (is_vtol(&status)) {
|
||||
status.is_rotary_wing = vtol_status.vtol_in_rw_mode;
|
||||
status.in_transition_mode = vtol_status.vtol_in_trans_mode;
|
||||
|
||||
@@ -1610,7 +1610,9 @@ MulticopterPositionControl::task_main()
|
||||
|
||||
/* 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
|
||||
* in this case the attitude setpoint is published by the mavlink app. Also do not publish
|
||||
* if the vehicle is a VTOL and it's just doing a transition (the VTOL attitude control module will generate
|
||||
* attitude setpoints for the transition).
|
||||
*/
|
||||
if (!(_control_mode.flag_control_offboard_enabled &&
|
||||
!(_control_mode.flag_control_position_enabled ||
|
||||
|
||||
Reference in New Issue
Block a user