Template Class ActionClient

Inheritance Relationships

Base Types

Class Documentation

template<typename ActionT, typename pGoalMsg = typename ActionT::Goal::SharedPtr, typename pFeedbackMsg = typename ActionT::Feedback::SharedPtr, typename wrappedResultMsg = typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult>
class ActionClient : public soar_ros::Output<typename ActionT::Goal::SharedPtr>, public soar_ros::Input<bool>, public soar_ros::Input<typename ActionT::Feedback::SharedPtr>, public soar_ros::Input<typename rclcpp_action::ClientGoalHandle<ActionT>::WrappedResult>, public soar_ros::Interface

Public Types

using GoalHandle = rclcpp_action::ClientGoalHandle<ActionT>

Public Functions

inline explicit ActionClient(sml::Agent *agent, rclcpp::Node::SharedPtr node, const std::string &action_name)
inline virtual ~ActionClient()
inline void send_goal_from_soar(const pGoalMsg &soar_goal)

Send a goal to the action server from a parsed Soar goal.

All future inputs for Soar must be inserted to queues to match the Soar processing cycle.

Parameters:

soar_goal – The goal message parsed from Soar

inline virtual std::string getTopic() override

Get the topic of the subscriber.

Returns:

inline virtual sml::Agent *getAgent() override

Get the agent of the current interface.

Returns:

Protected Functions

virtual pGoalMsg parse(sml::Identifier *id) = 0

Parse Soar working memory structure to a ROS message.

Parameters:

id

Returns:

virtual void parse(pFeedbackMsg msg) = 0
virtual void parse(wrappedResultMsg msg) = 0
inline virtual void parse(bool msg) override

This function must attach the ROS message T from m_r2sQueue to the Soar input link.

Soar usually requires a pAgent->Commit() to send the changes, but this is handled inside the SoarRunner::processInput() call.

The function is called inside the Interface::Input::process_r2s() function.

Parameters:

msg – The ROS2 message.