PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
px4_ros2::ModeBase Class Referenceabstract

Base class for a mode. More...

#include <px4_ros2/components/mode.hpp>

Inheritance diagram for px4_ros2::ModeBase:
px4_ros2::Context px4_ros2::MissionExecutor::MissionMode

Classes

struct  Settings
 

Public Types

using ModeID = uint8_t
 Mode ID, corresponds to nav_state.
 

Public Member Functions

 ModeBase (rclcpp::Node &node, Settings settings, const std::string &topic_namespace_prefix="")
 
 ModeBase (const ModeBase &)=delete
 
bool doRegister ()
 
virtual void checkArmingAndRunConditions (HealthAndArmingCheckReporter &reporter)
 
virtual void onActivate ()=0
 
virtual void onDeactivate ()=0
 
void setSetpointUpdateRate (float rate_hz)
 
virtual void updateSetpoint (float dt_s)
 
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
 

Static Public Attributes

static constexpr ModeID kModeIDInvalid = 0xff
 
static constexpr ModeID kModeIDPosctl = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_POSCTL
 
static constexpr ModeID kModeIDTakeoff
 
static constexpr ModeID kModeIDDescend = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_DESCEND
 
static constexpr ModeID kModeIDLand = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_LAND
 
static constexpr ModeID kModeIDRtl = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_RTL
 
static constexpr ModeID kModeIDPrecisionLand
 
static constexpr ModeID kModeIDLoiter
 

Protected Member Functions

void setSkipMessageCompatibilityCheck ()
 
void overrideRegistration (const std::shared_ptr< Registration > &registration)
 
void disableWatchdogTimer ()
 
bool defaultMessageCompatibilityCheck ()
 

Friends

class ModeExecutorBase
 

Detailed Description

Base class for a mode.

Member Function Documentation

◆ checkArmingAndRunConditions()

virtual void px4_ros2::ModeBase::checkArmingAndRunConditions ( HealthAndArmingCheckReporter reporter)
inlinevirtual

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

Reimplemented in px4_ros2::MissionExecutor::MissionMode.

◆ completed()

void px4_ros2::ModeBase::completed ( Result  result)

Mode completed signal. Call this when the mode is finished. A mode might never call this, but modes like RTL, Land or Takeoff are expected to signal their completion.

Parameters
result

◆ doRegister()

bool px4_ros2::ModeBase::doRegister ( )

Register the mode. Call this once on startup, unless there's an associated executor. This is a blocking method.

Returns
true on success

◆ modeRequirements()

RequirementFlags & px4_ros2::ModeBase::modeRequirements ( )
inline

Get / modify mode requirements. These are generally automatically set based on selected setpoint types, and are used to prevent arming or trigger failsafes.

◆ onActivate()

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

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

Implemented in px4_ros2::MissionExecutor::MissionMode.

◆ onDeactivate()

virtual void px4_ros2::ModeBase::onDeactivate ( )
pure virtual

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

Implemented in px4_ros2::MissionExecutor::MissionMode.

◆ setSetpointUpdateRate()

void px4_ros2::ModeBase::setSetpointUpdateRate ( float  rate_hz)

Set the update rate when the mode is active. This is set automatically from the configured setpoints, but can be set as needed.

Parameters
rate_hzset to 0 to disable

Member Data Documentation

◆ kModeIDLoiter

constexpr ModeID px4_ros2::ModeBase::kModeIDLoiter
staticconstexpr
Initial value:
=
px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_LOITER

◆ kModeIDPrecisionLand

constexpr ModeID px4_ros2::ModeBase::kModeIDPrecisionLand
staticconstexpr
Initial value:
=
px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_PRECLAND

◆ kModeIDTakeoff

constexpr ModeID px4_ros2::ModeBase::kModeIDTakeoff
staticconstexpr
Initial value:
=
px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_TAKEOFF

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