Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add AMS (Auto Maneuver System, aka emergency descend) mode support #676

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion core/px4_custom_mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,9 @@ enum PX4_CUSTOM_SUB_MODE_AUTO {
PX4_CUSTOM_SUB_MODE_AUTO_RTL,
PX4_CUSTOM_SUB_MODE_AUTO_LAND,
PX4_CUSTOM_SUB_MODE_AUTO_RTGS,
PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET
PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET,
PX4_CUSTOM_SUB_MODE_AUTO_PRECLAND,
PX4_CUSTOM_SUB_MODE_AUTO_AMS
};

union px4_custom_mode {
Expand Down
3 changes: 3 additions & 0 deletions core/system_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -845,6 +845,9 @@ SystemImpl::make_command_flight_mode(FlightMode flight_mode, uint8_t component_i
case FlightMode::OFFBOARD:
custom_mode = px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD;
break;
case FlightMode::AMS:
custom_sub_mode = px4::PX4_CUSTOM_SUB_MODE_AUTO_AMS;
break;
default:
LogErr() << "Unknown Flight mode.";
MAVLinkCommands::CommandLong empty_command{};
Expand Down
1 change: 1 addition & 0 deletions core/system_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ class SystemImpl {
MISSION,
FOLLOW_ME,
OFFBOARD,
AMS,
};

explicit SystemImpl(DronecodeSDKImpl &parent, uint8_t system_id, uint8_t component_id);
Expand Down
10 changes: 10 additions & 0 deletions plugins/action/action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,11 @@ Action::Result Action::return_to_launch() const
return _impl->return_to_launch();
}

Action::Result Action::auto_maneuver_system() const
{
return _impl->auto_maneuver_system();
}

Action::Result Action::transition_to_fixedwing() const
{
return _impl->transition_to_fixedwing();
Expand Down Expand Up @@ -90,6 +95,11 @@ void Action::return_to_launch_async(result_callback_t callback)
_impl->return_to_launch_async(callback);
}

void Action::auto_maneuver_system_async(result_callback_t callback)
{
_impl->auto_maneuver_system_async(callback);
}

void Action::transition_to_multicopter_async(result_callback_t callback)
{
_impl->transition_to_multicopter_async(callback);
Expand Down
11 changes: 11 additions & 0 deletions plugins/action/action_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,11 @@ Action::Result ActionImpl::return_to_launch() const
_parent->set_flight_mode(SystemImpl::FlightMode::RETURN_TO_LAUNCH));
}

Action::Result ActionImpl::auto_maneuver_system() const
{
return action_result_from_command_result(_parent->set_flight_mode(SystemImpl::FlightMode::AMS));
}

Action::Result ActionImpl::goto_location(double latitude_deg,
double longitude_deg,
float altitude_amsl_m,
Expand Down Expand Up @@ -370,6 +375,12 @@ void ActionImpl::return_to_launch_async(const Action::result_callback_t &callbac
std::bind(&ActionImpl::command_result_callback, _1, callback));
}

void ActionImpl::auto_maneuver_system_async(const Action::result_callback_t &callback)
{
_parent->set_flight_mode_async(SystemImpl::FlightMode::AMS,
std::bind(&ActionImpl::command_result_callback, _1, callback));
}

Action::Result ActionImpl::arming_allowed() const
{
// We want to wait up to 1.5 second, maybe we find out about the
Expand Down
2 changes: 2 additions & 0 deletions plugins/action/action_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ class ActionImpl : public PluginImplBase {
Action::Result takeoff() const;
Action::Result land() const;
Action::Result return_to_launch() const;
Action::Result auto_maneuver_system() const;
Action::Result
goto_location(double latitude_deg, double longitude_deg, float altitude_amsl_m, float yaw_deg);
Action::Result transition_to_fixedwing() const;
Expand All @@ -37,6 +38,7 @@ class ActionImpl : public PluginImplBase {
void takeoff_async(const Action::result_callback_t &callback);
void land_async(const Action::result_callback_t &callback);
void return_to_launch_async(const Action::result_callback_t &callback);
void auto_maneuver_system_async(const Action::result_callback_t &callback);
void transition_to_fixedwing_async(const Action::result_callback_t &callback);
void transition_to_multicopter_async(const Action::result_callback_t &callback);

Expand Down
24 changes: 23 additions & 1 deletion plugins/action/include/plugins/action/action.h
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ class Action : public PluginBase {
Result land() const;

/**
* @brief Send command to *return to the launch* (takeoff) position and *land* (asynchronous).
* @brief Send command to *return to the launch* (takeoff) position and *land* (synchronous).
*
* This switches the drone into [RTL mode](https://docs.px4.io/en/flight_modes/rtl.html) which
* generally means it will rise up to a certain altitude to clear any obstacles before heading
Expand All @@ -137,6 +137,17 @@ class Action : public PluginBase {
*/
Result return_to_launch() const;

/**
* @brief Send command to engage the *auto maneuver system (AMS)* (synchronous).
*
* This switches the drone into [AMS mode](https://docs.px4.io/en/flight_modes/ams.html) which
* means it will perform an emergency descend followed by a predefined behavior
* (loiter/land/...).
*
* @param callback Function to call with result of request.
*/
Action::Result auto_maneuver_system() const;

/**
* @brief Send command to reposition the vehicle to a specific WGS84 global position
*
Expand Down Expand Up @@ -241,6 +252,17 @@ class Action : public PluginBase {
*/
void return_to_launch_async(result_callback_t callback);

/**
* @brief Send command to engage the *auto maneuver system (AMS)* (asynchronous).
*
* This switches the drone into [AMS mode](https://docs.px4.io/en/flight_modes/ams.html) which
* means it will perform an emergency descend followed by a predefined behavior
* (loiter/land/...).
*
* @param callback Function to call with result of request.
*/
void auto_maneuver_system_async(result_callback_t callback);

/**
* @brief Send command to transition the drone to fixedwing (asynchronous).
*
Expand Down