Class LandBehavior

Inheritance Relationships

Base Type

  • public as2_behavior::BehaviorServer< as2_msgs::action::Land >

Class Documentation

class LandBehavior : public as2_behavior::BehaviorServer<as2_msgs::action::Land>

Public Types

using GoalHandleLand = rclcpp_action::ServerGoalHandle<as2_msgs::action::Land>
using PSME = as2_msgs::msg::PlatformStateMachineEvent

Public Functions

explicit LandBehavior(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
~LandBehavior()
void state_callback(const geometry_msgs::msg::TwistStamped::SharedPtr _twist_msg)
bool sendEventFSME(const int8_t _event)
bool sendDisarm()
bool process_goal(std::shared_ptr<const as2_msgs::action::Land::Goal> goal, as2_msgs::action::Land::Goal &new_goal)
bool on_activate(std::shared_ptr<const as2_msgs::action::Land::Goal> goal) override
bool on_modify(std::shared_ptr<const as2_msgs::action::Land::Goal> goal) override
virtual bool on_deactivate(const std::shared_ptr<std::string> &message) override
virtual bool on_pause(const std::shared_ptr<std::string> &message) override
virtual bool on_resume(const std::shared_ptr<std::string> &message) override
as2_behavior::ExecutionStatus on_run(const std::shared_ptr<const as2_msgs::action::Land::Goal> &goal, std::shared_ptr<as2_msgs::action::Land::Feedback> &feedback_msg, std::shared_ptr<as2_msgs::action::Land::Result> &result_msg) override
virtual void on_execution_end(const as2_behavior::ExecutionStatus &state) override