PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
px4_ros2::MissionExecutor::MissionModeExecutor Class Reference
Inheritance diagram for px4_ros2::MissionExecutor::MissionModeExecutor:
px4_ros2::ModeExecutorBase

Public Member Functions

 MissionModeExecutor (rclcpp::Node &node, const Settings &settings, ModeBase &owned_mode, const std::string &topic_namespace_prefix, MissionExecutor &mission_executor)
 
 MissionModeExecutor (const ModeExecutorBase &mode_executor_base)=delete
 
void onActivate () override
 
void onDeactivate (DeactivateReason reason) override
 
void onFailsafeDeferred () override
 
Result sendCommandSync (uint32_t command, float param1, float param2, float param3, float param4, float param5, float param6, float param7) override
 
void setRegistration (const std::shared_ptr< Registration > &registration)
 
- Public Member Functions inherited from px4_ros2::ModeExecutorBase
 ModeExecutorBase (const Settings &settings, ModeBase &owned_mode)
 
 ModeExecutorBase (const ModeExecutorBase &)=delete
 
bool doRegister ()
 
void scheduleMode (ModeBase::ModeID mode_id, const CompletedCallback &on_completed, bool forced=false)
 
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, bool run_preflight_checks=true)
 
void disarm (const CompletedCallback &on_completed, bool forced=false)
 
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)
 

Public Attributes

std::function< bool(uint32_t, float)> command_handler {nullptr}
 
std::function< void()> on_failsafe_deferred {nullptr}
 

Additional Inherited Members

- Public Types inherited from px4_ros2::ModeExecutorBase
enum class  DeactivateReason { FailsafeActivated , Other }
 
using CompletedCallback = std::function< void(Result)>
 
- Protected Member Functions inherited from px4_ros2::ModeExecutorBase
void setSkipMessageCompatibilityCheck ()
 
void overrideRegistration (const std::shared_ptr< Registration > &registration)
 

Member Function Documentation

◆ onActivate()

void px4_ros2::MissionExecutor::MissionModeExecutor::onActivate ( )
inlineoverridevirtual

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

Implements px4_ros2::ModeExecutorBase.

◆ onDeactivate()

void px4_ros2::MissionExecutor::MissionModeExecutor::onDeactivate ( DeactivateReason  reason)
inlineoverridevirtual

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

Implements px4_ros2::ModeExecutorBase.

◆ onFailsafeDeferred()

void px4_ros2::MissionExecutor::MissionModeExecutor::onFailsafeDeferred ( )
inlineoverridevirtual

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

See also
deferFailsafesSync()

Reimplemented from px4_ros2::ModeExecutorBase.

◆ sendCommandSync()

Result px4_ros2::MissionExecutor::MissionModeExecutor::sendCommandSync ( uint32_t  command,
float  param1,
float  param2,
float  param3,
float  param4,
float  param5,
float  param6,
float  param7 
)
inlineoverridevirtual

Send command and wait for ack/nack

Reimplemented from px4_ros2::ModeExecutorBase.


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