mavsdk::ActionServer Class Reference
#include: action_server.h
Provide vehicle actions (as a server) such as arming, taking off, and landing.
Data Structures
struct AllowableFlightModes
struct ArmDisarm
Public Types
Type | Description |
---|---|
enum FlightMode | Flight modes. |
enum Result | Possible results returned for action requests. |
std::function< void(Result)> ResultCallback | Callback type for asynchronous ActionServer calls. |
std::function< void(Result, ArmDisarm)> ArmDisarmCallback | Callback type for subscribe_arm_disarm. |
Handle< Result, ArmDisarm > ArmDisarmHandle | Handle type for subscribe_arm_disarm. |
std::function< void(Result, FlightMode)> FlightModeChangeCallback | Callback type for subscribe_flight_mode_change. |
Handle< Result, FlightMode > FlightModeChangeHandle | Handle type for subscribe_flight_mode_change. |
std::function< void(Result, bool)> TakeoffCallback | Callback type for subscribe_takeoff. |
Handle< Result, bool > TakeoffHandle | Handle type for subscribe_takeoff. |
std::function< void(Result, bool)> LandCallback | Callback type for subscribe_land. |
Handle< Result, bool > LandHandle | Handle type for subscribe_land. |
std::function< void(Result, bool)> RebootCallback | Callback type for subscribe_reboot. |
Handle< Result, bool > RebootHandle | Handle type for subscribe_reboot. |
std::function< void(Result, bool)> ShutdownCallback | Callback type for subscribe_shutdown. |
Handle< Result, bool > ShutdownHandle | Handle type for subscribe_shutdown. |
std::function< void(Result, bool)> TerminateCallback | Callback type for subscribe_terminate. |
Handle< Result, bool > TerminateHandle | Handle type for subscribe_terminate. |
Public Member Functions
Type | Name | Description |
---|---|---|
ActionServer (std::shared_ptr< ServerComponent > server_component) | Constructor. Creates the plugin for a ServerComponent instance. | |
~ActionServer () override | Destructor (internal use only). | |
ActionServer (const ActionServer & other) | Copy constructor. | |
ArmDisarmHandle | subscribe_arm_disarm (const ArmDisarmCallback & callback) | Subscribe to ARM/DISARM commands. |
void | unsubscribe_arm_disarm (ArmDisarmHandle handle) | Unsubscribe from subscribe_arm_disarm. |
FlightModeChangeHandle | subscribe_flight_mode_change (const FlightModeChangeCallback & callback) | Subscribe to DO_SET_MODE. |
void | unsubscribe_flight_mode_change (FlightModeChangeHandle handle) | Unsubscribe from subscribe_flight_mode_change. |
TakeoffHandle | subscribe_takeoff (const TakeoffCallback & callback) | Subscribe to takeoff command. |
void | unsubscribe_takeoff (TakeoffHandle handle) | Unsubscribe from subscribe_takeoff. |
LandHandle | subscribe_land (const LandCallback & callback) | Subscribe to land command. |
void | unsubscribe_land (LandHandle handle) | Unsubscribe from subscribe_land. |
RebootHandle | subscribe_reboot (const RebootCallback & callback) | Subscribe to reboot command. |
void | unsubscribe_reboot (RebootHandle handle) | Unsubscribe from subscribe_reboot. |
ShutdownHandle | subscribe_shutdown (const ShutdownCallback & callback) | Subscribe to shutdown command. |
void | unsubscribe_shutdown (ShutdownHandle handle) | Unsubscribe from subscribe_shutdown. |
TerminateHandle | subscribe_terminate (const TerminateCallback & callback) | Subscribe to terminate command. |
void | unsubscribe_terminate (TerminateHandle handle) | Unsubscribe from subscribe_terminate. |
Result | set_allow_takeoff (bool allow_takeoff)const | Can the vehicle takeoff. |
Result | set_armable (bool armable, bool force_armable)const | Can the vehicle arm when requested. |
Result | set_disarmable (bool disarmable, bool force_disarmable)const | Can the vehicle disarm when requested. |
Result | set_allowable_flight_modes (AllowableFlightModes flight_modes)const | Set which modes the vehicle can transition to (Manual always allowed) |
ActionServer::AllowableFlightModes | get_allowable_flight_modes () const | Get which modes the vehicle can transition to (Manual always allowed) |
const ActionServer & | operator= (const ActionServer &)=delete | Equality operator (object is not copyable). |
Constructor & Destructor Documentation
ActionServer()
mavsdk::ActionServer::ActionServer(std::shared_ptr< ServerComponent > server_component)
Constructor. Creates the plugin for a ServerComponent instance.
The plugin is typically created as shown below:
auto action_server = ActionServer(server_component);
Parameters
- std::shared_ptr< ServerComponent > server_component - The ServerComponent instance associated with this server plugin.
~ActionServer()
mavsdk::ActionServer::~ActionServer() override
Destructor (internal use only).
ActionServer()
mavsdk::ActionServer::ActionServer(const ActionServer &other)
Copy constructor.
Parameters
- const ActionServer& other -
Member Typdef Documentation
typedef ResultCallback
using mavsdk::ActionServer::ResultCallback = std::function<void(Result)>
Callback type for asynchronous ActionServer calls.
typedef ArmDisarmCallback
using mavsdk::ActionServer::ArmDisarmCallback = std::function<void(Result, ArmDisarm)>
Callback type for subscribe_arm_disarm.
typedef ArmDisarmHandle
using mavsdk::ActionServer::ArmDisarmHandle = Handle<Result, ArmDisarm>
Handle type for subscribe_arm_disarm.
typedef FlightModeChangeCallback
using mavsdk::ActionServer::FlightModeChangeCallback = std::function<void(Result, FlightMode)>
Callback type for subscribe_flight_mode_change.
typedef FlightModeChangeHandle
using mavsdk::ActionServer::FlightModeChangeHandle = Handle<Result, FlightMode>
Handle type for subscribe_flight_mode_change.
typedef TakeoffCallback
using mavsdk::ActionServer::TakeoffCallback = std::function<void(Result, bool)>
Callback type for subscribe_takeoff.
typedef TakeoffHandle
using mavsdk::ActionServer::TakeoffHandle = Handle<Result, bool>
Handle type for subscribe_takeoff.
typedef LandCallback
using mavsdk::ActionServer::LandCallback = std::function<void(Result, bool)>
Callback type for subscribe_land.
typedef LandHandle
using mavsdk::ActionServer::LandHandle = Handle<Result, bool>
Handle type for subscribe_land.
typedef RebootCallback
using mavsdk::ActionServer::RebootCallback = std::function<void(Result, bool)>
Callback type for subscribe_reboot.
typedef RebootHandle
using mavsdk::ActionServer::RebootHandle = Handle<Result, bool>
Handle type for subscribe_reboot.
typedef ShutdownCallback
using mavsdk::ActionServer::ShutdownCallback = std::function<void(Result, bool)>
Callback type for subscribe_shutdown.
typedef ShutdownHandle
using mavsdk::ActionServer::ShutdownHandle = Handle<Result, bool>
Handle type for subscribe_shutdown.
typedef TerminateCallback
using mavsdk::ActionServer::TerminateCallback = std::function<void(Result, bool)>
Callback type for subscribe_terminate.
typedef TerminateHandle
using mavsdk::ActionServer::TerminateHandle = Handle<Result, bool>
Handle type for subscribe_terminate.
Member Enumeration Documentation
enum FlightMode
Flight modes.
For more information about flight modes, check out https://docs.px4.io/master/en/config/flight_mode.html.
Value | Description |
---|---|
Unknown |
Mode not known. |
Ready |
Armed and ready to take off. |
Takeoff |
Taking off. |
Hold |
Holding (hovering in place (or circling for fixed-wing vehicles). |
Mission |
In mission. |
ReturnToLaunch |
Returning to launch position (then landing). |
Land |
Landing. |
Offboard |
In 'offboard' mode. |
FollowMe |
In 'follow-me' mode. |
Manual |
In 'Manual' mode. |
Altctl |
In 'Altitude Control' mode. |
Posctl |
In 'Position Control' mode. |
Acro |
In 'Acro' mode. |
Stabilized |
In 'Stabilize' mode. |
enum Result
Possible results returned for action requests.
Value | Description |
---|---|
Unknown |
Unknown result. |
Success |
Request was successful. |
NoSystem |
No system is connected. |
ConnectionError |
Connection error. |
Busy |
Vehicle is busy. |
CommandDenied |
Command refused by vehicle. |
CommandDeniedLandedStateUnknown |
Command refused because landed state is unknown. |
CommandDeniedNotLanded |
Command refused because vehicle not landed. |
Timeout |
Request timed out. |
VtolTransitionSupportUnknown |
Hybrid/VTOL transition support is unknown. |
NoVtolTransitionSupport |
Vehicle does not support hybrid/VTOL transitions. |
ParameterError |
Error getting or setting parameter. |
Next |
Intermediate message showing progress or instructions on the next steps. |
Member Function Documentation
subscribe_arm_disarm()
ArmDisarmHandle mavsdk::ActionServer::subscribe_arm_disarm(const ArmDisarmCallback &callback)
Subscribe to ARM/DISARM commands.
Parameters
- const ArmDisarmCallback& callback -
Returns
unsubscribe_arm_disarm()
void mavsdk::ActionServer::unsubscribe_arm_disarm(ArmDisarmHandle handle)
Unsubscribe from subscribe_arm_disarm.
Parameters
- ArmDisarmHandle handle -
subscribe_flight_mode_change()
FlightModeChangeHandle mavsdk::ActionServer::subscribe_flight_mode_change(const FlightModeChangeCallback &callback)
Subscribe to DO_SET_MODE.
Parameters
- const FlightModeChangeCallback& callback -
Returns
unsubscribe_flight_mode_change()
void mavsdk::ActionServer::unsubscribe_flight_mode_change(FlightModeChangeHandle handle)
Unsubscribe from subscribe_flight_mode_change.
Parameters
- FlightModeChangeHandle handle -
subscribe_takeoff()
TakeoffHandle mavsdk::ActionServer::subscribe_takeoff(const TakeoffCallback &callback)
Subscribe to takeoff command.
Parameters
- const TakeoffCallback& callback -
Returns
unsubscribe_takeoff()
void mavsdk::ActionServer::unsubscribe_takeoff(TakeoffHandle handle)
Unsubscribe from subscribe_takeoff.
Parameters
- TakeoffHandle handle -
subscribe_land()
LandHandle mavsdk::ActionServer::subscribe_land(const LandCallback &callback)
Subscribe to land command.
Parameters
- const LandCallback& callback -
Returns
unsubscribe_land()
void mavsdk::ActionServer::unsubscribe_land(LandHandle handle)
Unsubscribe from subscribe_land.
Parameters
- LandHandle handle -
subscribe_reboot()
RebootHandle mavsdk::ActionServer::subscribe_reboot(const RebootCallback &callback)
Subscribe to reboot command.
Parameters
- const RebootCallback& callback -
Returns
unsubscribe_reboot()
void mavsdk::ActionServer::unsubscribe_reboot(RebootHandle handle)
Unsubscribe from subscribe_reboot.
Parameters
- RebootHandle handle -
subscribe_shutdown()
ShutdownHandle mavsdk::ActionServer::subscribe_shutdown(const ShutdownCallback &callback)
Subscribe to shutdown command.
Parameters
- const ShutdownCallback& callback -
Returns
unsubscribe_shutdown()
void mavsdk::ActionServer::unsubscribe_shutdown(ShutdownHandle handle)
Unsubscribe from subscribe_shutdown.
Parameters
- ShutdownHandle handle -
subscribe_terminate()
TerminateHandle mavsdk::ActionServer::subscribe_terminate(const TerminateCallback &callback)
Subscribe to terminate command.
Parameters
- const TerminateCallback& callback -
Returns
unsubscribe_terminate()
void mavsdk::ActionServer::unsubscribe_terminate(TerminateHandle handle)
Unsubscribe from subscribe_terminate.
Parameters
- TerminateHandle handle -
set_allow_takeoff()
Result mavsdk::ActionServer::set_allow_takeoff(bool allow_takeoff) const
Can the vehicle takeoff.
This function is blocking.
Parameters
- bool allow_takeoff -
Returns
Result - Result of request.
set_armable()
Result mavsdk::ActionServer::set_armable(bool armable, bool force_armable) const
Can the vehicle arm when requested.
This function is blocking.
Parameters
- bool armable -
- bool force_armable -
Returns
Result - Result of request.
set_disarmable()
Result mavsdk::ActionServer::set_disarmable(bool disarmable, bool force_disarmable) const
Can the vehicle disarm when requested.
This function is blocking.
Parameters
- bool disarmable -
- bool force_disarmable -
Returns
Result - Result of request.
set_allowable_flight_modes()
Result mavsdk::ActionServer::set_allowable_flight_modes(AllowableFlightModes flight_modes) const
Set which modes the vehicle can transition to (Manual always allowed)
This function is blocking.
Parameters
- AllowableFlightModes flight_modes -
Returns
Result - Result of request.
get_allowable_flight_modes()
ActionServer::AllowableFlightModes mavsdk::ActionServer::get_allowable_flight_modes() const
Get which modes the vehicle can transition to (Manual always allowed)
This function is blocking.
Returns
ActionServer::AllowableFlightModes - Result of request.
operator=()
const ActionServer& mavsdk::ActionServer::operator=(const ActionServer &)=delete
Equality operator (object is not copyable).
Parameters
- const ActionServer& -
Returns
const ActionServer & -