AutoAPMS
Resilient Robot Mission Management
|
#include <auto_apms_px4/mode_executor.hpp>
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< ActionContextType > | action_context_ptr_ |
Definition at line 28 of file mode_executor.hpp.
using FlightMode = VehicleCommandClient::FlightMode |
Definition at line 42 of file mode_executor.hpp.
using TaskStatus = auto_apms_core::TaskStatus |
Definition at line 47 of file mode_executor.hpp.
|
explicit |
Definition at line 94 of file mode_executor.hpp.
|
explicit |
Definition at line 107 of file mode_executor.hpp.
|
explicit |
Definition at line 119 of file mode_executor.hpp.
|
protected |
Definition at line 245 of file mode_executor.hpp.
|
protectedvirtual |
Definition at line 336 of file mode_executor.hpp.
|
protectedvirtual |
Definition at line 344 of file mode_executor.hpp.
|
protectedvirtual |
Definition at line 353 of file mode_executor.hpp.
|
protected |
Definition at line 362 of file mode_executor.hpp.