Mission execution state machine.
More...
#include <px4_ros2/mission/mission_executor.hpp>
|
|
| MissionExecutor (const std::string &mode_name, const Configuration &configuration, rclcpp::Node &node, const std::string &topic_namespace_prefix="") |
| |
|
bool | doRegister () |
| |
|
void | setMission (const Mission &mission) |
| |
|
void | resetMission () |
| |
|
const Mission & | mission () const |
| |
|
void | onActivated (const std::function< void()> &callback) |
| |
|
void | onDeactivated (const std::function< void()> &callback) |
| |
| void | onProgressUpdate (const std::function< void(int)> &callback) |
| |
|
void | onCompleted (const std::function< void()> &callback) |
| |
|
void | onFailsafeDeferred (const std::function< void()> &callback) |
| |
|
void | onReadynessUpdate (const std::function< void(bool ready, const std::vector< std::string > &errors)> &callback) |
| |
| void | onActivityInfoChange (const std::function< void(const std::optional< std::string > &)> &callback) |
| | Registers a callback to be invoked when the activity information changes. This callback provides a way to react to updates in the current activity info. More...
|
| |
| void | setActivityInfo (const std::optional< std::string > &activity_info) |
| | Sets a string with extra information about the current activity. This provides more specific context than the generic navigation state from PX4. For example, while the navigation state might report "mission," this string can specify "takeoff," "landing," or "surveying." The string should be concise (around 30 characters) to be easily digestible. More...
|
| |
| bool | deferFailsafes (bool enabled, int timeout_s=0) |
| |
|
bool | controlAutoSetHome (bool enabled) |
| |
| void | abort () |
| |
|
|
class | ActionHandler |
| |
|
class | ActionStateKeeper |
| |
Mission execution state machine.
◆ abort()
| void px4_ros2::MissionExecutor::abort |
( |
| ) |
|
Abort a currently running mission. This will trigger the onFailure action (which can be customized). The abort reason will be set to 'other'.
◆ deferFailsafes()
| bool px4_ros2::MissionExecutor::deferFailsafes |
( |
bool |
enabled, |
|
|
int |
timeout_s = 0 |
|
) |
| |
Enable/disable deferring failsafes. While enabled (and the mission executor is active), 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)
- Parameters
-
| enabled | |
| timeout_s | 0=system default, -1=no timeout |
- Returns
- true on success
◆ onActivityInfoChange()
| void px4_ros2::MissionExecutor::onActivityInfoChange |
( |
const std::function< void(const std::optional< std::string > &)> & |
callback | ) |
|
|
inline |
Registers a callback to be invoked when the activity information changes. This callback provides a way to react to updates in the current activity info.
- Parameters
-
| callback | The function to call with the new optional activity info string. |
◆ onProgressUpdate()
| void px4_ros2::MissionExecutor::onProgressUpdate |
( |
const std::function< void(int)> & |
callback | ) |
|
|
inline |
Get notified when the current mission item changes. This is the index into the current mission items that is currently being executed (i.e. if it is a waypoint, the current target waypoint)
◆ setActivityInfo()
| void px4_ros2::MissionExecutor::setActivityInfo |
( |
const std::optional< std::string > & |
activity_info | ) |
|
Sets a string with extra information about the current activity. This provides more specific context than the generic navigation state from PX4. For example, while the navigation state might report "mission," this string can specify "takeoff," "landing," or "surveying." The string should be concise (around 30 characters) to be easily digestible.
- Parameters
-
| activity_info | An optional string containing additional information about the current action. |
The documentation for this class was generated from the following file: