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

Public Member Functions

 MissionMode (rclcpp::Node &node, const Settings &settings, const std::string &topic_namespace_prefix, MissionExecutor &mission_executor)
 
 MissionMode (const ModeBase &mode_base)=delete
 
void checkArmingAndRunConditions (HealthAndArmingCheckReporter &reporter) override
 
void onActivate () override
 
void onDeactivate () override
 
void updateSetpoint (float dt_s) override
 
void disableWatchdogTimer ()
 
- Public Member Functions inherited from px4_ros2::ModeBase
 ModeBase (rclcpp::Node &node, Settings settings, const std::string &topic_namespace_prefix="")
 
 ModeBase (const ModeBase &)=delete
 
bool doRegister ()
 
void setSetpointUpdateRate (float rate_hz)
 
void completed (Result result)
 
ModeID id () const
 
bool isArmed () const
 
bool isActive () const
 
ConfigOverridesconfigOverrides ()
 
RequirementFlagsmodeRequirements ()
 
- Public Member Functions inherited from px4_ros2::Context
 Context (rclcpp::Node &node, std::string topic_namespace_prefix="")
 
rclcpp::Node & node ()
 
const std::string & topicNamespacePrefix () const
 

Additional Inherited Members

- Public Types inherited from px4_ros2::ModeBase
using ModeID = uint8_t
 Mode ID, corresponds to nav_state.
 
- Static Public Attributes inherited from px4_ros2::ModeBase
static constexpr ModeID kModeIDInvalid = 0xff
 
static constexpr ModeID kModeIDPosctl
 
static constexpr ModeID kModeIDTakeoff
 
static constexpr ModeID kModeIDDescend
 
static constexpr ModeID kModeIDLand
 
static constexpr ModeID kModeIDRtl
 
static constexpr ModeID kModeIDPrecisionLand
 
static constexpr ModeID kModeIDLoiter
 
- Protected Member Functions inherited from px4_ros2::ModeBase
void setSkipMessageCompatibilityCheck ()
 
void overrideRegistration (const std::shared_ptr< Registration > &registration)
 
void disableWatchdogTimer ()
 
bool defaultMessageCompatibilityCheck ()
 

Member Function Documentation

◆ checkArmingAndRunConditions()

void px4_ros2::MissionExecutor::MissionMode::checkArmingAndRunConditions ( HealthAndArmingCheckReporter reporter)
inlineoverridevirtual

Report any custom mode requirements. This is called regularly, also while the mode is active.

Reimplemented from px4_ros2::ModeBase.

◆ onActivate()

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

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

Implements px4_ros2::ModeBase.

◆ onDeactivate()

void px4_ros2::MissionExecutor::MissionMode::onDeactivate ( )
inlineoverridevirtual

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

Implements px4_ros2::ModeBase.


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