SMACC2
Loading...
Searching...
No Matches
cp_nav2_action_interface.hpp
Go to the documentation of this file.
1// Copyright 2024 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#pragma once
16
17#include <geometry_msgs/msg/pose_stamped.hpp>
18#include <nav2_msgs/action/navigate_to_pose.hpp>
20#include <smacc2/component.hpp>
22
23#include <functional>
24#include <future>
25
26namespace cl_nav2z
27{
28namespace components
29{
30using namespace smacc2;
31
33{
34public:
35 // Type aliases for convenience
36 using ActionType = nav2_msgs::action::NavigateToPose;
37 using Goal = ActionType::Goal;
38 using Result = ActionType::Result;
39 using Feedback = ActionType::Feedback;
40 using GoalHandle = rclcpp_action::ClientGoalHandle<ActionType>;
41 using WrappedResult = typename GoalHandle::WrappedResult;
43
44 // Nav2-specific signals for external subscribers
49
50 // Nav2-specific event posting functions (set during orthogonal allocation)
51 std::function<void(const WrappedResult &)> postNavigationSuccessEvent;
52 std::function<void(const WrappedResult &)> postNavigationAbortedEvent;
53 std::function<void(const WrappedResult &)> postNavigationCancelledEvent;
54 std::function<void(const Feedback &)> postNavigationFeedbackEvent;
55
57 virtual ~CpNav2ActionInterface() = default;
58
59 // Public API for behaviors and other components
60 std::shared_future<typename GoalHandle::SharedPtr> sendNavigationGoal(
61 const geometry_msgs::msg::PoseStamped & target)
62 {
63 if (!actionClient_)
64 {
65 RCLCPP_ERROR(getLogger(), "[CpNav2ActionInterface] Action client not available!");
66 throw std::runtime_error("Action client not initialized");
67 }
68
69 Goal goal;
70 goal.pose = target;
71
72 // Set default behavior_tree if not specified
73 if (goal.behavior_tree.empty())
74 {
75 goal.behavior_tree = ""; // Let Nav2 use default behavior tree
76 }
77
78 RCLCPP_INFO_STREAM(
79 getLogger(), "[CpNav2ActionInterface] Sending navigation goal to: "
80 << "x=" << target.pose.position.x << ", y=" << target.pose.position.y
81 << ", frame=" << target.header.frame_id);
82
83 return actionClient_->sendGoal(goal);
84 }
85
86 std::shared_future<typename GoalHandle::SharedPtr> sendGoal(Goal & goal)
87 {
88 if (!actionClient_)
89 {
90 RCLCPP_ERROR(getLogger(), "[CpNav2ActionInterface] Action client not available!");
91 throw std::runtime_error("Action client not initialized");
92 }
93
94 return actionClient_->sendGoal(goal);
95 }
96
98 {
99 if (!actionClient_)
100 {
101 RCLCPP_WARN(getLogger(), "[CpNav2ActionInterface] Action client not available for cancel!");
102 return false;
103 }
104
105 RCLCPP_INFO(getLogger(), "[CpNav2ActionInterface] Cancelling navigation goal");
106 return actionClient_->cancelGoal();
107 }
108
109 bool isNavigationServerReady() const { return actionClient_ && actionClient_->isServerReady(); }
110
112 {
113 if (actionClient_)
114 {
115 actionClient_->waitForServer();
116 }
117 }
118
119 // Component lifecycle
120 template <typename TOrthogonal, typename TClient>
122 {
123 // Set up nav2-specific event posting functions
124 postNavigationSuccessEvent = [this](const WrappedResult & result)
125 {
127 this->postEvent(ev);
128 };
129
130 postNavigationAbortedEvent = [this](const WrappedResult & result)
131 {
133 this->postEvent(ev);
134 };
135
136 postNavigationCancelledEvent = [this](const WrappedResult & result)
137 {
139 this->postEvent(ev);
140 };
141
142 postNavigationFeedbackEvent = [this](const Feedback & feedback)
143 {
145 //ev->feedbackMessage = feedback;
146 this->postEvent(ev);
147 };
148
149 RCLCPP_INFO(getLogger(), "[CpNav2ActionInterface] Component initialized");
150 }
151
152 void onInitialize() override
153 {
154 RCLCPP_INFO(getLogger(), "[CpNav2ActionInterface] Component initializing");
155
156 // Require the underlying action client component
157 this->requiresComponent(actionClient_, ComponentRequirement::HARD);
158
159 // Wire up signal connections from action client to nav2-specific signals
160 if (actionClient_)
161 {
162 // Connect action client signals to our nav2-specific signals and event posting using method pointers
163 // these are the main smacc signals in the action client, our navigation client behavior subscribes to them and reacts accordingly
164 // each derived behavior do something different in reaction to these signals
169
170 RCLCPP_INFO(getLogger(), "[CpNav2ActionInterface] Signal connections established");
171 }
172 else
173 {
174 RCLCPP_ERROR(
175 getLogger(), "[CpNav2ActionInterface] Action client not found during initialization!");
176 }
177 }
178
179 // Access to underlying action client for advanced usage
181
182 // These methods are used by other client behavior and components that want to react to navigation events.
183 template <typename T>
184 boost::signals2::connection onNavigationSucceeded(
185 void (T::*callback)(const WrappedResult &), T * object)
186 {
188 onNavigationSucceeded_, callback, object);
189 }
190
191 template <typename T>
192 boost::signals2::connection onNavigationAborted(
193 void (T::*callback)(const WrappedResult &), T * object)
194 {
195 return this->getStateMachine()->createSignalConnection(onNavigationAborted_, callback, object);
196 }
197
198 template <typename T>
199 boost::signals2::connection onNavigationCancelled(
200 void (T::*callback)(const WrappedResult &), T * object)
201 {
203 onNavigationCancelled_, callback, object);
204 }
205
206 template <typename T>
207 boost::signals2::connection onNavigationFeedback(
208 void (T::*callback)(const Feedback &), T * object)
209 {
210 return this->getStateMachine()->createSignalConnection(onNavigationFeedback_, callback, object);
211 }
212
213private:
215
216 // Event translation callbacks
218 {
219 RCLCPP_INFO(getLogger(), "[CpNav2ActionInterface] Navigation succeeded");
222 {
224 }
225 }
226
228 {
229 RCLCPP_WARN(getLogger(), "[CpNav2ActionInterface] Navigation aborted");
230 onNavigationAborted_(result);
232 {
234 }
235 }
236
238 {
239 RCLCPP_INFO(getLogger(), "[CpNav2ActionInterface] Navigation cancelled");
242 {
244 }
245 }
246
248 {
249 RCLCPP_DEBUG(getLogger(), "[CpNav2ActionInterface] Navigation feedback received");
250 onNavigationFeedback_(feedback);
252 {
254 }
255 }
256};
257
258} // namespace components
259} // namespace cl_nav2z
std::function< void(const Feedback &)> postNavigationFeedbackEvent
smacc2::SmaccSignal< void(const WrappedResult &)> onNavigationCancelled_
std::function< void(const WrappedResult &)> postNavigationSuccessEvent
smacc2::SmaccSignal< void(const WrappedResult &)> onNavigationSucceeded_
smacc2::SmaccSignal< void(const WrappedResult &)> onNavigationAborted_
boost::signals2::connection onNavigationCancelled(void(T::*callback)(const WrappedResult &), T *object)
smacc2::SmaccSignal< void(const Feedback &)> onNavigationFeedback_
boost::signals2::connection onNavigationSucceeded(void(T::*callback)(const WrappedResult &), T *object)
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)
std::shared_future< typename GoalHandle::SharedPtr > sendNavigationGoal(const geometry_msgs::msg::PoseStamped &target)
std::function< void(const WrappedResult &)> postNavigationCancelledEvent
rclcpp_action::ClientGoalHandle< ActionType > GoalHandle
void onNavigationCancelledCallback(const WrappedResult &result)
boost::signals2::connection onNavigationFeedback(void(T::*callback)(const Feedback &), T *object)
void onNavigationSuccessCallback(const WrappedResult &result)
smacc2::client_core_components::CpActionClient< ActionType > * actionClient_
void onNavigationAbortedCallback(const WrappedResult &result)
std::function< void(const WrappedResult &)> postNavigationAbortedEvent
void onNavigationFeedbackCallback(const Feedback &feedback)
boost::signals2::connection onNavigationAborted(void(T::*callback)(const WrappedResult &), T *object)
ISmaccStateMachine * getStateMachine()
rclcpp::Logger getLogger() const
void requiresComponent(TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist)
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)