PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
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 (const Settings &settings, ModeBase &owned_mode) | |
ModeExecutorBase (const ModeExecutorBase &)=delete | |
bool | doRegister () |
virtual void | onActivate ()=0 |
virtual void | onDeactivate (DeactivateReason reason)=0 |
virtual void | onFailsafeDeferred () |
virtual 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, 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 |
ModeBase & | ownedMode () |
int | id () const |
rclcpp::Node & | node () |
ConfigOverrides & | configOverrides () |
bool | deferFailsafesSync (bool enabled, int timeout_s=0) |
Protected Member Functions | |
void | setSkipMessageCompatibilityCheck () |
void | overrideRegistration (const std::shared_ptr< Registration > ®istration) |
Base class for a mode executor.
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:
If the executor is in charge, this method will wait for the FMU for acknowledgement (to avoid race conditions)
enabled | |
timeout_s | 0=system default, -1=no timeout |
bool px4_ros2::ModeExecutorBase::doRegister | ( | ) |
Register the mode executor. Call this once on startup. This is a blocking method.
|
pure virtual |
Called whenever the mode is activated, also if the vehicle is disarmed
Implemented in px4_ros2::MissionExecutor::MissionModeExecutor.
|
pure virtual |
Called whenever the mode is deactivated, also if the vehicle is disarmed
Implemented in px4_ros2::MissionExecutor::MissionModeExecutor.
|
inlinevirtual |
Called when failsafes are currently being deferred, and the FMU wants to trigger a failsafe.
Reimplemented in px4_ros2::MissionExecutor::MissionModeExecutor.
void px4_ros2::ModeExecutorBase::scheduleMode | ( | ModeBase::ModeID | mode_id, |
const CompletedCallback & | on_completed, | ||
bool | forced = false |
||
) |
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.
The forced parameter, when set to true, allows to be able to force the scheduling of the modes when the drone is disarmed
|
virtual |
Send command and wait for ack/nack
Reimplemented in px4_ros2::MissionExecutor::MissionModeExecutor.