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 ev->resultMessage = result;
128 this->postEvent(ev);
129 };
130
131 postNavigationAbortedEvent = [this](const WrappedResult & result)
132 {
134 ev->resultMessage = result;
135 this->postEvent(ev);
136 };
137
138 postNavigationCancelledEvent = [this](const WrappedResult & result)
139 {
141 ev->resultMessage = result;
142 this->postEvent(ev);
143 };
144
145 postNavigationFeedbackEvent = [this](const Feedback & feedback)
146 {
148 ev->feedbackMessage = feedback;
149 this->postEvent(ev);
150 };
151
152 RCLCPP_INFO(getLogger(), "[CpNav2ActionInterface] Component initialized");
153 }
154
155 void onInitialize() override
156 {
157 RCLCPP_INFO(getLogger(), "[CpNav2ActionInterface] Component initializing");
158
159 // Require the underlying action client component
160 this->requiresComponent(actionClient_, ComponentRequirement::HARD);
161
162 // Wire up signal connections from action client to nav2-specific signals
163 if (actionClient_)
164 {
165 // Connect action client signals to our nav2-specific signals and event posting using method pointers
166 // these are the main smacc signals in the action client, our navigation client behavior subscribes to them and reacts accordingly
167 // each derived behavior do something different in reaction to these signals
172
173 RCLCPP_INFO(getLogger(), "[CpNav2ActionInterface] Signal connections established");
174 }
175 else
176 {
177 RCLCPP_ERROR(
178 getLogger(), "[CpNav2ActionInterface] Action client not found during initialization!");
179 }
180 }
181
182 // Access to underlying action client for advanced usage
184
185 // These methods are used by other client behavior and components that want to react to navigation events.
186 template <typename T>
188 void (T::*callback)(const WrappedResult &), T * object)
189 {
191 onNavigationSucceeded_, callback, object);
192 }
193
194 template <typename T>
196 void (T::*callback)(const WrappedResult &), T * object)
197 {
198 return this->getStateMachine()->createSignalConnection(onNavigationAborted_, callback, object);
199 }
200
201 template <typename T>
203 void (T::*callback)(const WrappedResult &), T * object)
204 {
206 onNavigationCancelled_, callback, object);
207 }
208
209 template <typename T>
211 void (T::*callback)(const Feedback &), T * object)
212 {
213 return this->getStateMachine()->createSignalConnection(onNavigationFeedback_, callback, object);
214 }
215
216private:
218
219 // Event translation callbacks
221 {
222 RCLCPP_INFO(getLogger(), "[CpNav2ActionInterface] Navigation succeeded");
225 {
227 }
228 }
229
231 {
232 RCLCPP_WARN(getLogger(), "[CpNav2ActionInterface] Navigation aborted");
233 onNavigationAborted_(result);
235 {
237 }
238 }
239
241 {
242 RCLCPP_INFO(getLogger(), "[CpNav2ActionInterface] Navigation cancelled");
245 {
247 }
248 }
249
251 {
252 RCLCPP_DEBUG(getLogger(), "[CpNav2ActionInterface] Navigation feedback received");
253 onNavigationFeedback_(feedback);
255 {
257 }
258 }
259};
260
261} // namespace components
262} // namespace cl_nav2z
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_
smacc2::SmaccSignal< void(const Feedback &)> onNavigationFeedback_
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)
smacc2::SmaccSignalConnection onNavigationAborted(void(T::*callback)(const WrappedResult &), T *object)
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)
void onNavigationSuccessCallback(const WrappedResult &result)
smacc2::SmaccSignalConnection onNavigationCancelled(void(T::*callback)(const WrappedResult &), T *object)
smacc2::client_core_components::CpActionClient< ActionType > * actionClient_
void onNavigationAbortedCallback(const WrappedResult &result)
std::function< void(const WrappedResult &)> postNavigationAbortedEvent
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