17#include <geometry_msgs/msg/pose_stamped.hpp>
18#include <nav2_msgs/action/navigate_to_pose.hpp>
37 using Goal = ActionType::Goal;
40 using GoalHandle = rclcpp_action::ClientGoalHandle<ActionType>;
61 const geometry_msgs::msg::PoseStamped & target)
65 RCLCPP_ERROR(
getLogger(),
"[CpNav2ActionInterface] Action client not available!");
66 throw std::runtime_error(
"Action client not initialized");
73 if (goal.behavior_tree.empty())
75 goal.behavior_tree =
"";
79 getLogger(),
"[CpNav2ActionInterface] Sending navigation goal to: "
80 <<
"x=" << target.pose.position.x <<
", y=" << target.pose.position.y
81 <<
", frame=" << target.header.frame_id);
86 std::shared_future<typename GoalHandle::SharedPtr>
sendGoal(
Goal & goal)
90 RCLCPP_ERROR(
getLogger(),
"[CpNav2ActionInterface] Action client not available!");
91 throw std::runtime_error(
"Action client not initialized");
101 RCLCPP_WARN(
getLogger(),
"[CpNav2ActionInterface] Action client not available for cancel!");
105 RCLCPP_INFO(
getLogger(),
"[CpNav2ActionInterface] Cancelling navigation goal");
120 template <
typename TOrthogonal,
typename TClient>
127 ev->resultMessage = result;
134 ev->resultMessage = result;
141 ev->resultMessage = result;
148 ev->feedbackMessage = feedback;
152 RCLCPP_INFO(
getLogger(),
"[CpNav2ActionInterface] Component initialized");
157 RCLCPP_INFO(
getLogger(),
"[CpNav2ActionInterface] Component initializing");
173 RCLCPP_INFO(
getLogger(),
"[CpNav2ActionInterface] Signal connections established");
178 getLogger(),
"[CpNav2ActionInterface] Action client not found during initialization!");
186 template <
typename T>
191 onNavigationSucceeded_, callback,
object);
194 template <
typename T>
201 template <
typename T>
206 onNavigationCancelled_, callback,
object);
209 template <
typename T>
211 void (T::*callback)(
const Feedback &), T *
object)
222 RCLCPP_INFO(
getLogger(),
"[CpNav2ActionInterface] Navigation succeeded");
232 RCLCPP_WARN(
getLogger(),
"[CpNav2ActionInterface] Navigation aborted");
242 RCLCPP_INFO(
getLogger(),
"[CpNav2ActionInterface] Navigation cancelled");
252 RCLCPP_DEBUG(
getLogger(),
"[CpNav2ActionInterface] Navigation feedback received");
bool isNavigationServerReady() const
std::function< void(const Feedback &)> postNavigationFeedbackEvent
smacc2::SmaccSignal< void(const WrappedResult &)> onNavigationCancelled_
smacc2::SmaccSignalConnection onNavigationFeedback(void(T::*callback)(const Feedback &), T *object)
std::function< void(const WrappedResult &)> postNavigationSuccessEvent
smacc2::SmaccSignal< void(const WrappedResult &)> onNavigationSucceeded_
smacc2::SmaccSignalConnection onNavigationSucceeded(void(T::*callback)(const WrappedResult &), T *object)
smacc2::SmaccSignal< void(const WrappedResult &)> onNavigationAborted_
virtual ~CpNav2ActionInterface()=default
CpNav2ActionInterface()=default
smacc2::SmaccSignal< void(const Feedback &)> onNavigationFeedback_
void onComponentInitialization()
void waitForNavigationServer()
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)
ActionType::Result Result
smacc2::SmaccSignalConnection onNavigationAborted(void(T::*callback)(const WrappedResult &), T *object)
std::shared_future< typename GoalHandle::SharedPtr > sendNavigationGoal(const geometry_msgs::msg::PoseStamped &target)
typename GoalHandle::WrappedResult WrappedResult
ActionType::Feedback Feedback
std::function< void(const WrappedResult &)> postNavigationCancelledEvent
rclcpp_action::ClientGoalHandle< ActionType > GoalHandle
void onNavigationCancelledCallback(const WrappedResult &result)
ActionClient * getActionClient() const
void onNavigationSuccessCallback(const WrappedResult &result)
smacc2::SmaccSignalConnection onNavigationCancelled(void(T::*callback)(const WrappedResult &), T *object)
smacc2::client_core_components::CpActionClient< ActionType > * actionClient_
void onInitialize() override
void onNavigationAbortedCallback(const WrappedResult &result)
std::function< void(const WrappedResult &)> postNavigationAbortedEvent
nav2_msgs::action::NavigateToPose ActionType
void onNavigationFeedbackCallback(const Feedback &feedback)
ISmaccStateMachine * getStateMachine()
rclcpp::Logger getLogger() const
void requiresComponent(TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
smacc2::SmaccSignalConnection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
boost::signals2::connection SmaccSignalConnection