Class GoToBase

Inheritance Relationships

Derived Types

Class Documentation

class GoToBase

Subclassed by go_to_plugin_position::Plugin, go_to_plugin_trajectory::Plugin

Public Types

using GoalHandleGoTo = rclcpp_action::ServerGoalHandle<as2_msgs::action::GoToWaypoint>

Public Functions

inline GoToBase()
inline virtual ~GoToBase()
inline void initialize(as2::Node *node_ptr, std::shared_ptr<as2::tf::TfHandler> tf_handler, go_to_plugin_params &params)
inline void state_callback(geometry_msgs::msg::PoseStamped &pose_msg, geometry_msgs::msg::TwistStamped &twist_msg)
inline void platform_info_callback(const as2_msgs::msg::PlatformInfo::SharedPtr msg)
inline bool on_activate(std::shared_ptr<const as2_msgs::action::GoToWaypoint::Goal> goal)
inline bool on_modify(std::shared_ptr<const as2_msgs::action::GoToWaypoint::Goal> goal)
inline bool on_deactivate(const std::shared_ptr<std::string> &message)
inline bool on_pause(const std::shared_ptr<std::string> &message)
inline bool on_resume(const std::shared_ptr<std::string> &message)
inline void on_execution_end(const as2_behavior::ExecutionStatus &state)
inline as2_behavior::ExecutionStatus on_run(const std::shared_ptr<const as2_msgs::action::GoToWaypoint::Goal> goal, std::shared_ptr<as2_msgs::action::GoToWaypoint::Feedback> &feedback_msg, std::shared_ptr<as2_msgs::action::GoToWaypoint::Result> &result_msg)

Protected Functions

inline virtual void ownInit()
virtual bool own_activate(as2_msgs::action::GoToWaypoint::Goal &goal) = 0
inline virtual bool own_modify(as2_msgs::action::GoToWaypoint::Goal &goal)
virtual bool own_deactivate(const std::shared_ptr<std::string> &message) = 0
inline virtual bool own_pause(const std::shared_ptr<std::string> &message)
inline virtual bool own_resume(const std::shared_ptr<std::string> &message)
virtual void own_execution_end(const as2_behavior::ExecutionStatus &state) = 0
virtual as2_behavior::ExecutionStatus own_run() = 0
inline void sendHover()

Protected Attributes

as2::Node *node_ptr_
std::shared_ptr<as2::tf::TfHandler> tf_handler = nullptr
as2_msgs::action::GoToWaypoint::Goal goal_
as2_msgs::action::GoToWaypoint::Feedback feedback_
as2_msgs::action::GoToWaypoint::Result result_
int platform_state_
go_to_plugin_params params_
geometry_msgs::msg::PoseStamped actual_pose_
bool localization_flag_