mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 16:07:35 +08:00
support orbit command in fixed wing mode
Signed-off-by: RomanBapst <bapstroman@gmail.com> commander: support orbit mode for fixed wings Signed-off-by: RomanBapst <bapstroman@gmail.com> FwPositionControl: publish orbit status Signed-off-by: RomanBapst <bapstroman@gmail.com> commander:reject orbit mode while doing a vtol transition Signed-off-by: RomanBapst <bapstroman@gmail.com> FixedWingPositionControl: explicitly cast waypoint for Orbit status FixedwingPositionControl: fill missing orbit_status fields navigator_main: handle reposition/orbit corner cases - set orbit rotation direction correctly - send mavlink message when orbit is rejected FixedWingPositionControl: correctly report rotation direction in orbit_status navigator: hack to not break orbit while doing altitude changes Signed-off-by: RomanBapst <bapstroman@gmail.com> navigator: set cruise throttle for orbit command Signed-off-by: RomanBapst <bapstroman@gmail.com>
This commit is contained in:
committed by
Silvan Fuhrer
parent
93eb0162e5
commit
d84b0296d2
@@ -1211,13 +1211,28 @@ Commander::handle_command(const vehicle_command_s &cmd)
|
||||
|
||||
case vehicle_command_s::VEHICLE_CMD_DO_ORBIT:
|
||||
|
||||
// Switch to orbit state and let the orbit task handle the command further
|
||||
if (TRANSITION_DENIED != main_state_transition(_status, commander_state_s::MAIN_STATE_ORBIT, _status_flags,
|
||||
_internal_state)) {
|
||||
transition_result_t main_ret;
|
||||
|
||||
if (_status.in_transition_mode) {
|
||||
main_ret = TRANSITION_DENIED;
|
||||
|
||||
} else if (_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) {
|
||||
// for fixed wings the behavior of orbit is the same as loiter
|
||||
main_ret = main_state_transition(_status, commander_state_s::MAIN_STATE_AUTO_LOITER,
|
||||
_status_flags, _internal_state);
|
||||
|
||||
} else {
|
||||
// Switch to orbit state and let the orbit task handle the command further
|
||||
main_ret = main_state_transition(_status, commander_state_s::MAIN_STATE_ORBIT, _status_flags,
|
||||
_internal_state);
|
||||
}
|
||||
|
||||
if ((main_ret != TRANSITION_DENIED)) {
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
|
||||
} else {
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Orbit command rejected");
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
Reference in New Issue
Block a user