Template Class CpActionClient
Defined in File cp_action_client.hpp
Inheritance Relationships
Base Type
public smacc2::ISmaccComponent(Class ISmaccComponent)
Class Documentation
-
template<typename ActionType>
class CpActionClient : public smacc2::ISmaccComponent Public Types
-
using ActionClient = rclcpp_action::Client<ActionType>
-
using Goal = typename ActionType::Goal
-
using Feedback = typename ActionType::Feedback
-
using Result = typename ActionType::Result
-
using GoalHandle = rclcpp_action::ClientGoalHandle<ActionType>
-
using WrappedResult = typename GoalHandle::WrappedResult
-
using SendGoalOptions = typename ActionClient::SendGoalOptions
-
using GoalResponseCallback = std::function<void(std::shared_future<typename GoalHandle::SharedPtr>)>
-
using FeedbackCallback = typename GoalHandle::FeedbackCallback
-
using ResultCallback = typename GoalHandle::ResultCallback
Public Functions
-
CpActionClient() = default
-
inline CpActionClient(const std::string &actionServerName)
-
virtual ~CpActionClient() = default
-
inline std::shared_future<typename GoalHandle::SharedPtr> sendGoal(Goal &goal, typename smacc2::SmaccSignal<void(const WrappedResult&)>::WeakPtr resultCallback = typename smacc2::SmaccSignal<void(const WrappedResult&)>::WeakPtr())
-
inline bool cancelGoal()
-
inline bool isServerReady() const
-
inline void waitForServer()
-
inline virtual void onInitialize() override
-
template<typename TOrthogonal, typename TSourceObject>
inline void onComponentInitialization()
-
template<typename T>
inline smacc2::SmaccSignalConnection onSucceeded(void (T::* callback)(const WrappedResult&), T *object)
-
template<typename T>
inline smacc2::SmaccSignalConnection onAborted(void (T::* callback)(const WrappedResult&), T *object)
-
template<typename T>
inline smacc2::SmaccSignalConnection onCancelled(void (T::* callback)(const WrappedResult&), T *object)
-
template<typename T>
inline smacc2::SmaccSignalConnection onFeedback(void (T::* callback)(const Feedback&), T *object)
-
inline std::shared_ptr<ActionClient> getActionClient() const
Public Members
-
std::optional<std::string> actionServerName
-
std::optional<std::chrono::milliseconds> serverTimeout
-
smacc2::SmaccSignal<void(const WrappedResult&)> onActionSucceeded_
-
smacc2::SmaccSignal<void(const WrappedResult&)> onActionAborted_
-
smacc2::SmaccSignal<void(const WrappedResult&)> onActionCancelled_
-
smacc2::SmaccSignal<void(const Feedback&)> onActionFeedback_
-
smacc2::SmaccSignal<void()> onGoalAccepted_
-
smacc2::SmaccSignal<void()> onGoalRejected_
-
std::function<void(const WrappedResult&)> postSuccessEvent
-
std::function<void(const WrappedResult&)> postAbortedEvent
-
std::function<void(const WrappedResult&)> postCancelledEvent
-
using ActionClient = rclcpp_action::Client<ActionType>