AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
ModeExecutor< ActionT > Class Template Reference

#include <auto_apms_px4/mode_executor.hpp>

Inheritance diagram for ModeExecutor< ActionT >:

Public Types

using FlightMode = VehicleCommandClient::FlightMode
 
using TaskStatus = auto_apms_core::TaskStatus
 
- Public Types inherited from Task< ActionT >
using Status = TaskStatus
 
using ActionContextType = ActionContext<ActionT>
 
using Goal = typename ActionContextType::Goal
 
using Feedback = typename ActionContextType::Feedback
 
using Result = typename ActionContextType::Result
 
using GoalHandle = typename ActionContextType::GoalHandle
 

Public Member Functions

 ModeExecutor (const std::string &name, rclcpp::Node::SharedPtr node_ptr, std::shared_ptr< ActionContextType > action_context_ptr, uint8_t mode_id, bool deactivate_before_completion=true, std::chrono::milliseconds execution_interval=DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=DEFAULT_VALUE_FEEDBACK_INTERVAL)
 
 ModeExecutor (const std::string &name, const rclcpp::NodeOptions &options, uint8_t mode_id, bool deactivate_before_completion=true, std::chrono::milliseconds execution_interval=DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=DEFAULT_VALUE_FEEDBACK_INTERVAL)
 
 ModeExecutor (const std::string &name, const rclcpp::NodeOptions &options, FlightMode flight_mode, bool deactivate_before_completion=true, std::chrono::milliseconds execution_interval=DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=DEFAULT_VALUE_FEEDBACK_INTERVAL)
 
- Public Member Functions inherited from Task< ActionT >
 Task (const std::string &name, rclcpp::Node::SharedPtr node_ptr, std::shared_ptr< ActionContextType > action_context_ptr, std::chrono::milliseconds execution_interval=DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=DEFAULT_VALUE_FEEDBACK_INTERVAL)
 
 Task (const std::string &name, rclcpp::Node::SharedPtr node_ptr, std::chrono::milliseconds execution_interval=DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=DEFAULT_VALUE_FEEDBACK_INTERVAL)
 
 Task (const std::string &name, const rclcpp::NodeOptions &options, std::chrono::milliseconds execution_interval=DEFAULT_VALUE_EXECUTION_INTERVAL, std::chrono::milliseconds feedback_interval=DEFAULT_VALUE_FEEDBACK_INTERVAL)
 
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface () const
 

Protected Member Functions

bool isCurrentNavState (uint8_t nav_state)
 
virtual bool sendActivationCommand (const VehicleCommandClient &client, std::shared_ptr< const Goal > goal_ptr)
 
virtual bool isCompleted (std::shared_ptr< const Goal > goal_ptr, const px4_msgs::msg::VehicleStatus &vehicle_status)
 
virtual void setFeedback (std::shared_ptr< Feedback > feedback_ptr, const px4_msgs::msg::VehicleStatus &vehicle_status)
 
uint8_t getModeID () const
 

Additional Inherited Members

- Static Public Attributes inherited from Task< ActionT >
static constexpr std::chrono::milliseconds DEFAULT_VALUE_EXECUTION_INTERVAL { 10 }
 
static constexpr std::chrono::milliseconds DEFAULT_VALUE_FEEDBACK_INTERVAL { 200 }
 
static constexpr char PARAM_NAME_FEEDBACK_INTERVAL [] = "feedback_interval_ms"
 
- Protected Attributes inherited from Task< ActionT >
rclcpp::Node::SharedPtr node_ptr_
 
std::shared_ptr< ActionContextTypeaction_context_ptr_
 

Detailed Description

template<class ActionT>
class auto_apms_px4::ModeExecutor< ActionT >

Definition at line 28 of file mode_executor.hpp.

Member Typedef Documentation

◆ FlightMode

template<class ActionT >
using FlightMode = VehicleCommandClient::FlightMode

Definition at line 42 of file mode_executor.hpp.

◆ TaskStatus

template<class ActionT >
using TaskStatus = auto_apms_core::TaskStatus

Definition at line 47 of file mode_executor.hpp.

Constructor & Destructor Documentation

◆ ModeExecutor() [1/3]

template<class ActionT >
ModeExecutor ( const std::string & name,
rclcpp::Node::SharedPtr node_ptr,
std::shared_ptr< ActionContextType > action_context_ptr,
uint8_t mode_id,
bool deactivate_before_completion = true,
std::chrono::milliseconds execution_interval = DEFAULT_VALUE_EXECUTION_INTERVAL,
std::chrono::milliseconds feedback_interval = DEFAULT_VALUE_FEEDBACK_INTERVAL )
explicit

Definition at line 94 of file mode_executor.hpp.

◆ ModeExecutor() [2/3]

template<class ActionT >
ModeExecutor ( const std::string & name,
const rclcpp::NodeOptions & options,
uint8_t mode_id,
bool deactivate_before_completion = true,
std::chrono::milliseconds execution_interval = DEFAULT_VALUE_EXECUTION_INTERVAL,
std::chrono::milliseconds feedback_interval = DEFAULT_VALUE_FEEDBACK_INTERVAL )
explicit

Definition at line 107 of file mode_executor.hpp.

◆ ModeExecutor() [3/3]

template<class ActionT >
ModeExecutor ( const std::string & name,
const rclcpp::NodeOptions & options,
FlightMode flight_mode,
bool deactivate_before_completion = true,
std::chrono::milliseconds execution_interval = DEFAULT_VALUE_EXECUTION_INTERVAL,
std::chrono::milliseconds feedback_interval = DEFAULT_VALUE_FEEDBACK_INTERVAL )
explicit

Definition at line 119 of file mode_executor.hpp.

Member Function Documentation

◆ isCurrentNavState()

template<class ActionT >
bool isCurrentNavState ( uint8_t nav_state)
protected

Definition at line 245 of file mode_executor.hpp.

◆ sendActivationCommand()

template<class ActionT >
bool sendActivationCommand ( const VehicleCommandClient & client,
std::shared_ptr< const Goal > goal_ptr )
protectedvirtual

Definition at line 336 of file mode_executor.hpp.

◆ isCompleted()

template<class ActionT >
bool isCompleted ( std::shared_ptr< const Goal > goal_ptr,
const px4_msgs::msg::VehicleStatus & vehicle_status )
protectedvirtual

Definition at line 344 of file mode_executor.hpp.

◆ setFeedback()

template<class ActionT >
void setFeedback ( std::shared_ptr< Feedback > feedback_ptr,
const px4_msgs::msg::VehicleStatus & vehicle_status )
protectedvirtual

Definition at line 353 of file mode_executor.hpp.

◆ getModeID()

template<class ActionT >
uint8_t getModeID ( ) const
protected

Definition at line 362 of file mode_executor.hpp.


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