PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
px4_ros2::ModeExecutorBase Class Referenceabstract

Base class for a mode executor. More...

#include <px4_ros2/components/mode_executor.hpp>

Classes

struct  Settings
 

Public Types

enum class  DeactivateReason { FailsafeActivated , Other }
 
using CompletedCallback = std::function< void(Result)>
 

Public Member Functions

 ModeExecutorBase (rclcpp::Node &node, const Settings &settings, ModeBase &owned_mode, const std::string &topic_namespace_prefix="")
 
 ModeExecutorBase (const ModeExecutorBase &)=delete
 
bool doRegister ()
 
virtual void onActivate ()=0
 
virtual void onDeactivate (DeactivateReason reason)=0
 
virtual void onFailsafeDeferred ()
 
Result sendCommandSync (uint32_t command, float param1=NAN, float param2=NAN, float param3=NAN, float param4=NAN, float param5=NAN, float param6=NAN, float param7=NAN)
 
void scheduleMode (ModeBase::ModeID mode_id, const CompletedCallback &on_completed)
 
void takeoff (const CompletedCallback &on_completed, float altitude=NAN, float heading=NAN)
 
void land (const CompletedCallback &on_completed)
 
void rtl (const CompletedCallback &on_completed)
 
void arm (const CompletedCallback &on_completed)
 
void waitReadyToArm (const CompletedCallback &on_completed)
 
void waitUntilDisarmed (const CompletedCallback &on_completed)
 
bool isInCharge () const
 
bool isArmed () const
 
ModeBaseownedMode ()
 
int id () const
 
rclcpp::Node & node ()
 
ConfigOverridesconfigOverrides ()
 
bool deferFailsafesSync (bool enabled, int timeout_s=0)
 

Detailed Description

Base class for a mode executor.

Member Function Documentation

◆ deferFailsafesSync()

bool px4_ros2::ModeExecutorBase::deferFailsafesSync ( bool  enabled,
int  timeout_s = 0 
)

Enable/disable deferring failsafes. While enabled (and the executor is in charge), most failsafes are prevented from being triggered until the given timeout is exceeded. Some failsafes that cannot be prevented:

  • vehicle exceeds attitude limits (can be disabled via parameters)
  • the mode cannot run (some mode requirements are not met, such as no position estimate)

If the executor is in charge, this method will wait for the FMU for acknowledgement (to avoid race conditions)

Parameters
enabled
timeout_s0=system default, -1=no timeout
Returns
true on success

◆ doRegister()

bool px4_ros2::ModeExecutorBase::doRegister ( )

Register the mode executor. Call this once on startup. This is a blocking method.

Returns
true on success

◆ onActivate()

virtual void px4_ros2::ModeExecutorBase::onActivate ( )
pure virtual

Called whenever the mode is activated, also if the vehicle is disarmed

◆ onDeactivate()

virtual void px4_ros2::ModeExecutorBase::onDeactivate ( DeactivateReason  reason)
pure virtual

Called whenever the mode is deactivated, also if the vehicle is disarmed

◆ onFailsafeDeferred()

virtual void px4_ros2::ModeExecutorBase::onFailsafeDeferred ( )
inlinevirtual

Called when failsafes are currently being deferred, and the FMU wants to trigger a failsafe.

See also
deferFailsafesSync()

◆ scheduleMode()

void px4_ros2::ModeExecutorBase::scheduleMode ( ModeBase::ModeID  mode_id,
const CompletedCallback &  on_completed 
)

Switch to a mode with a callback when it is finished. The callback is also executed when the mode is deactivated. If there's already a mode scheduling active, the previous one is cancelled.

◆ sendCommandSync()

Result px4_ros2::ModeExecutorBase::sendCommandSync ( uint32_t  command,
float  param1 = NAN,
float  param2 = NAN,
float  param3 = NAN,
float  param4 = NAN,
float  param5 = NAN,
float  param6 = NAN,
float  param7 = NAN 
)

Send command and wait for ack/nack


The documentation for this class was generated from the following file: