Template Class BehaviorServer

Inheritance Relationships

Base Type

  • public as2::Node

Class Documentation

template<typename actionT>
class BehaviorServer : public as2::Node

Public Types

using GoalHandleAction = rclcpp_action::ServerGoalHandle<actionT>
using BehaviorStatus = as2_msgs::msg::BehaviorStatus
using start_srv = typename actionT::Impl::SendGoalService
using modify_srv = start_srv
using result_srv = typename actionT::Impl::GetResultService
using feedback_msg = typename actionT::Impl::FeedbackMessage
using goal_status_msg = typename actionT::Impl::GoalStatusMessage
using cancel_srv = typename actionT::Impl::CancelGoalService

Public Functions

void register_action()
rclcpp_action::GoalResponse handleGoal(const rclcpp_action::GoalUUID &uuid, std::shared_ptr<const typename actionT::Goal> goal)
rclcpp_action::CancelResponse handleCancel(const std::shared_ptr<GoalHandleAction> goal_handle)
void handleAccepted(const std::shared_ptr<GoalHandleAction> goal_handle)
BehaviorServer(const std::string &name, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
virtual bool on_activate(std::shared_ptr<const typename actionT::Goal> goal)
virtual bool on_modify(std::shared_ptr<const typename actionT::Goal> goal)
virtual bool on_deactivate(const std::shared_ptr<std::string> &message)
virtual bool on_pause(const std::shared_ptr<std::string> &message)
virtual bool on_resume(const std::shared_ptr<std::string> &message)
inline virtual void on_execution_end(const ExecutionStatus &state)
virtual ExecutionStatus on_run(const typename std::shared_ptr<const typename actionT::Goal> &goal, typename std::shared_ptr<typename actionT::Feedback> &feedback_msg, typename std::shared_ptr<typename actionT::Result> &result_msg)
bool activate(std::shared_ptr<const typename actionT::Goal> goal)
void modify(std::shared_ptr<const typename actionT::Goal> goal)
void deactivate(const typename std_srvs::srv::Trigger::Request::SharedPtr goal, typename std_srvs::srv::Trigger::Response::SharedPtr result)
void pause(const typename std_srvs::srv::Trigger::Request::SharedPtr goal, typename std_srvs::srv::Trigger::Response::SharedPtr result)
void resume(const typename std_srvs::srv::Trigger::Request::SharedPtr goal, typename std_srvs::srv::Trigger::Response::SharedPtr result)
void run(const typename std::shared_ptr<GoalHandleAction> &goal_handle_action)
inline void timer_callback()
void publish_behavior_status()

Public Members

std::string action_name_
rclcpp_action::Server<actionT>::SharedPtr action_server_
std::shared_ptr<GoalHandleAction> goal_handle_
as2_msgs::msg::BehaviorStatus behavior_status_