Template Class SimpleActionClient

Class Documentation

template<typename ACTION_TYPE>
class SimpleActionClient

Simple wrapper around rclcpp action client for easier usage. Assumes only one action at a time.

Public Types

using FeedbackCallback = std::function<void(const typename ACTION_TYPE::Feedback&)>
using ResultCallback = std::function<void(const ResultCode&, const typename ACTION_TYPE::Result&)>

Public Functions

inline SimpleActionClient(rclcpp::Node::SharedPtr node, const std::string &action_namespace, bool wait_for_server = true)
inline void waitForServer()

Waits indefinitely for the server to come up. Will print a message after 10 seconds.

inline void sendGoal(const typename ACTION_TYPE::Goal &goal_msg, ResultCallback resultCB = nullptr, FeedbackCallback feedbackCB = nullptr)

Send a goal, and return immediately.

inline ACTION_TYPE::Result &execute(const typename ACTION_TYPE::Goal &goal_msg, FeedbackCallback feedbackCB = nullptr)

Send a goal and wait for the result.

Note

: Does not return the ResultCode

Protected Functions

inline void goalResponseCallback(std::shared_future<typename rclcpp_action::ClientGoalHandle<ACTION_TYPE>::SharedPtr> future)
inline void feedbackCallback(typename rclcpp_action::ClientGoalHandle<ACTION_TYPE>::SharedPtr, const std::shared_ptr<const typename ACTION_TYPE::Feedback> feedback)
inline void resultCallback(const typename rclcpp_action::ClientGoalHandle<ACTION_TYPE>::WrappedResult &result)
inline void executeResultCallback(ResultCode, const typename ACTION_TYPE::Result &result)

Protected Attributes

rclcpp_action::Client<ACTION_TYPE>::SharedPtr client_
ACTION_TYPE::Result default_result_
ACTION_TYPE::Result execute_result_
bool execute_result_recieved_
FeedbackCallback feedback_cb_
ResultCallback result_cb_
rclcpp::Node::SharedPtr node_
rclcpp::Logger LOGGER
const std::string &action_namespace_
std::string info_string_