Handler passed to custom actions to run modes, actions and trajectories.
More...
#include <px4_ros2/mission/mission_executor.hpp>
|
|
| ActionHandler (MissionExecutor &mission_executor) |
| |
|
void | runMode (ModeBase::ModeID mode_id, const std::function< void()> &on_completed, const std::function< void()> &on_failure=nullptr) |
| |
| void | runModeTakeoff (float altitude, float heading, const std::function< void()> &on_completed, const std::function< void()> &on_failure=nullptr) |
| | Trigger a takeoff. More...
|
| |
|
void | runAction (const std::string &action_name, const ActionArguments &arguments, const std::function< void()> &on_completed) |
| |
|
void | runTrajectory (const std::shared_ptr< Mission > &trajectory, const std::function< void()> &on_completed, bool stop_at_last_item=true) |
| |
|
TrajectoryOptions | getTrajectoryOptions () const |
| | get the current trajectory config options
|
| |
|
void | clearTrajectoryOptions () |
| | Reset the current trajectory config options to the mission defaults.
|
| |
| void | setTrajectoryOptions (const TrajectoryOptions &options) |
| | Override the trajectory config options. More...
|
| |
| void | setActvityInfo (const std::string &activity_info) |
| | Sets the activity info for the mission executor. This method forwards the provided activity string to the underlying mission executor, making it externally accessible. This string provides a concise description of the current action. More...
|
| |
|
void | clearActivityInfo () |
| | Clears the activity information. This method sets the activity info of the mission executor to std::nullopt. It gets called when we switch to the next waypoint, mission deactivated or aborted .
|
| |
|
std::optional< int > | getCurrentMissionIndex () const |
| |
| void | setCurrentMissionIndex (int index) |
| | Set the current mission index. More...
|
| |
|
bool | currentActionSupportsResumeFromLanded () const |
| |
| std::unique_ptr< ActionStateKeeper > | storeState (const std::string &action_name, const ActionArguments &arguments) |
| | store the state of a continuous action More...
|
| |
|
const Mission & | mission () const |
| |
| bool | deferFailsafes (bool enabled, int timeout_s=0) |
| | enable/disable deferral of failsafes More...
|
| |
|
bool | controlAutoSetHome (bool enabled) |
| |
| void | onFailsafeDeferred (const std::function< void()> &callback) |
| | register callback for failsafe notification More...
|
| |
| bool | isValid () const |
| | Check if the handler is still valid. More...
|
| |
Handler passed to custom actions to run modes, actions and trajectories.
◆ deferFailsafes()
| bool px4_ros2::ActionHandler::deferFailsafes |
( |
bool |
enabled, |
|
|
int |
timeout_s = 0 |
|
) |
| |
|
inline |
enable/disable deferral of failsafes
- Parameters
-
| enabled | |
| timeout_s | 0=system default, -1=no timeout |
- Returns
- true on success
◆ isValid()
| bool px4_ros2::ActionHandler::isValid |
( |
| ) |
const |
|
inline |
Check if the handler is still valid.
If the handler is invalid, it cannot be used anymore. It will be set invalid when the mission is aborted, or deactivated. This is useful for actions that use timers to run actions.
◆ onFailsafeDeferred()
| void px4_ros2::ActionHandler::onFailsafeDeferred |
( |
const std::function< void()> & |
callback | ) |
|
|
inline |
register callback for failsafe notification
The callback is triggerd when a failsafe occurs while deferral is enabled.
◆ runModeTakeoff()
| void px4_ros2::ActionHandler::runModeTakeoff |
( |
float |
altitude, |
|
|
float |
heading, |
|
|
const std::function< void()> & |
on_completed, |
|
|
const std::function< void()> & |
on_failure = nullptr |
|
) |
| |
|
inline |
Trigger a takeoff.
- Parameters
-
| altitude | optional altitude AMSL [m], set to NAN to use the vehicle default |
| heading | optional heading [rad] from North, set to NAN to use the current heading |
| on_completed | callback to execute when the takeoff is completed |
| on_failure | optional callback to execute when the takeoff fails (if not set, abort is called instead) |
◆ setActvityInfo()
| void px4_ros2::ActionHandler::setActvityInfo |
( |
const std::string & |
activity_info | ) |
|
|
inline |
Sets the activity info for the mission executor. This method forwards the provided activity string to the underlying mission executor, making it externally accessible. This string provides a concise description of the current action.
- Parameters
-
| activity_info | The string describing the current action. |
◆ setCurrentMissionIndex()
| void px4_ros2::ActionHandler::setCurrentMissionIndex |
( |
int |
index | ) |
|
Set the current mission index.
This is primarily for the onResume action, in case the mission should be resumed at a different index.
When called as part of another action, the index will still be increased, and thus continue at the next item.
◆ setTrajectoryOptions()
| void px4_ros2::ActionHandler::setTrajectoryOptions |
( |
const TrajectoryOptions & |
options | ) |
|
|
inline |
Override the trajectory config options.
The values that are not set will be kept as they were before
◆ storeState()
store the state of a continuous action
This is used to restore the state when the mission is interrupted (e.g. by the user or a failsafe) and continued later on. When restoring, the action will be called with the provided arguments.
This can be used for example, for a camera trigger command that continuous to run in the background.
- Parameters
-
| action_name | Name of the calling action |
| arguments | Arguments to the action for restoring the action |
- Returns
- A token that should be stored. It can be deleted when the action stops or gets deactivated
The documentation for this class was generated from the following file: