SMACC2
Loading...
Searching...
No Matches
cp_waypoints_navigator.cpp
Go to the documentation of this file.
1// Copyright 2021 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/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#include <tf2/transform_datatypes.h>
22#include <yaml-cpp/yaml.h>
23
24#include <ament_index_cpp/get_package_share_directory.hpp>
25#include <cl_nav2z/cl_nav2z.hpp>
26#include <cl_nav2z/common.hpp>
32#include <fstream>
33#include <rclcpp/rclcpp.hpp>
34
35namespace cl_nav2z
36{
37using namespace std::chrono_literals;
38using namespace smacc2;
39
40CpWaypointNavigatorBase::CpWaypointNavigatorBase() : currentWaypoint_(0), waypoints_(0) {}
41
43
45
47
49{
50 this->requiresComponent(nav2ActionInterface_, ComponentRequirement::HARD);
51}
52
60
68
71{
74 RCLCPP_WARN(
75 getLogger(), "[CpWaypointNavigator] Goal result received, incrementing waypoint index: %ld",
78
79 this->notifyGoalReached();
80
82}
83
85{
88}
89
91{
93 if (currentWaypoint_ >= (long)waypoints_.size() - 1)
94 currentWaypoint_ = (long)waypoints_.size() - 1;
95}
96
98{
99 bool found = false;
100
101 auto previousWaypoint = currentWaypoint_;
102
103 while (!found && currentWaypoint_ < (long)waypoints_.size())
104 {
105 auto & nextName = waypointsNames_[currentWaypoint_];
106 RCLCPP_INFO(
107 getLogger(), "[CpWaypointNavigator] seeking ,%ld/%ld candidate waypoint: %s",
108 currentWaypoint_, waypoints_.size(), nextName.c_str());
109 if (name == nextName)
110 {
111 found = true;
112 RCLCPP_INFO(
113 getLogger(), "[CpWaypointNavigator] found target waypoint: %s == %s-> found",
114 nextName.c_str(), name.c_str());
115 }
116 else
117 {
118 RCLCPP_INFO(
119 getLogger(), "[CpWaypointNavigator] current waypoint: %s != %s -> forward",
120 nextName.c_str(), name.c_str());
122 }
123 }
124
125 if (found)
126 {
127 if (currentWaypoint_ >= (long)waypoints_.size() - 1)
128 currentWaypoint_ = (long)waypoints_.size() - 1;
129 }
130 else // search backwards
131 {
132 currentWaypoint_ = previousWaypoint;
133 while (!found && currentWaypoint_ > 0)
134 {
135 auto & nextName = waypointsNames_[currentWaypoint_];
136 RCLCPP_INFO(
137 getLogger(), "[CpWaypointNavigator] seeking , candidate waypoint: %s", nextName.c_str());
138 if (name == nextName)
139 {
140 found = true;
141 RCLCPP_INFO(
142 getLogger(), "[CpWaypointNavigator] found target waypoint: %s == %s-> found",
143 nextName.c_str(), name.c_str());
144 }
145 else
146 {
147 RCLCPP_INFO(
148 getLogger(), "[CpWaypointNavigator] current waypoint: %s != %s -> rewind",
149 nextName.c_str(), name.c_str());
151 }
152 }
153 }
154
155 RCLCPP_INFO(
156 getLogger(), "[CpWaypointNavigator] seekName( %s), previous index: %ld, after index: %ld",
157 name.c_str(), previousWaypoint, currentWaypoint_);
158}
159
161 std::string parameter_name, std::string yaml_file_package_name)
162{
163 // if it is the first time and the waypoints navigator is not configured
164 std::string planfilepath;
165 planfilepath = getNode()->declare_parameter(parameter_name, planfilepath);
166 RCLCPP_INFO(getLogger(), "waypoints plan parameter: %s", planfilepath.c_str());
167 if (getNode()->get_parameter(parameter_name, planfilepath))
168 {
169 std::string package_share_directory =
170 ament_index_cpp::get_package_share_directory(yaml_file_package_name);
171
172 RCLCPP_INFO(getLogger(), "file macro path: %s", planfilepath.c_str());
173
174 boost::replace_all(planfilepath, "$(pkg_share)", package_share_directory);
175
176 RCLCPP_INFO(getLogger(), "package share path: %s", package_share_directory.c_str());
177 RCLCPP_INFO(getLogger(), "waypoints plan file: %s", planfilepath.c_str());
178
179 this->loadWayPointsFromFile(planfilepath);
180 RCLCPP_INFO(getLogger(), "waypoints plan: %s", planfilepath.c_str());
181 }
182 else
183 {
184 RCLCPP_ERROR(getLogger(), "waypoints plan file not found: NONE");
185 }
186}
187
189{
190 if (succeddedNav2ZClientConnection_.connected())
191 {
192 this->succeddedNav2ZClientConnection_.disconnect();
193 this->cancelledNav2ZClientConnection_.disconnect();
194 this->abortedNav2ZClientConnection_.disconnect();
195 }
196}
197
198std::optional<std::shared_future<
199 std::shared_ptr<rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose>>>>
200CpWaypointNavigator::sendNextGoal(std::optional<NavigateNextWaypointOptions> options)
201{
202 if (currentWaypoint_ >= 0 && currentWaypoint_ < (int)waypoints_.size())
203 {
204 auto & next = waypoints_[currentWaypoint_];
205
206 std::string nextName;
207 if ((long)waypointsNames_.size() > currentWaypoint_)
208 {
210 RCLCPP_INFO(
211 getLogger(), "[CpWaypointNavigator] sending goal, waypoint: %s", nextName.c_str());
212 }
213 else
214 {
215 RCLCPP_INFO(
216 getLogger(), "[CpWaypointNavigator] sending goal, waypoint: %ld", currentWaypoint_);
217 }
218
219 nav2_msgs::action::NavigateToPose::Goal goal;
220 CpPose * p;
221 this->requiresComponent(p, ComponentRequirement::HARD);
222 auto pose = p->toPoseMsg();
223
224 // configuring goal
225 goal.pose.header.frame_id = p->getReferenceFrame();
226 //goal.pose.header.stamp = getNode()->now();
227 goal.pose.pose = next;
228
229 cl_nav2z::CpPlannerSwitcher * plannerSwitcher;
230 this->requiresComponent(plannerSwitcher, ComponentRequirement::HARD);
231
232 plannerSwitcher->setDefaultPlanners(false);
233 if (options && options->controllerName_)
234 {
235 RCLCPP_WARN(
236 getLogger(), "[WaypointsNavigator] override controller: %s",
237 options->controllerName_->c_str());
238
239 plannerSwitcher->setDesiredController(*options->controllerName_);
240 }
241 else
242 {
243 RCLCPP_WARN(getLogger(), "[WaypointsNavigator] Configuring default planners");
244 }
245
246 cl_nav2z::CpGoalCheckerSwitcher * goalCheckerSwitcher;
247 // this->requiresComponent(goalCheckerSwitcher, ComponentRequirement::HARD);
248 this->requiresComponent(goalCheckerSwitcher, ComponentRequirement::SOFT);
249
250 if (options && options->goalCheckerName_)
251 {
252 RCLCPP_WARN(
253 getLogger(), "[WaypointsNavigator] override goal checker: %s",
254 options->goalCheckerName_->c_str());
255
256 goalCheckerSwitcher->setGoalCheckerId(*options->goalCheckerName_);
257 }
258 else
259 {
260 RCLCPP_WARN(getLogger(), "[WaypointsNavigator] Configuring default goal checker");
261 goalCheckerSwitcher->setGoalCheckerId("goal_checker");
262 }
263
264 plannerSwitcher->commitPublish();
265
266 // publish stuff
267 // rclcpp::sleep_for(5s);
268
269 RCLCPP_INFO(getLogger(), "[WaypointsNavigator] Getting odom tracker");
270
272 requiresComponent(odomTracker, ComponentRequirement::SOFT);
273
274 if (odomTracker != nullptr)
275 {
276 RCLCPP_INFO(getLogger(), "[WaypointsNavigator] Storing path in odom tracker");
277
278 auto pathname = this->owner_->getStateMachine()->getCurrentState()->getName() + " - " +
279 getName() + " - " + nextName;
280 odomTracker->pushPath(pathname);
281 odomTracker->setStartPoint(pose);
283 }
284
285 // SEND GOAL
286 // if (!succeddedNav2ZClientConnection_.connected())
287 // {
288 // this->succeddedNav2ZClientConnection_ =
289 // client_->onSucceeded(&WaypointNavigator::onGoalReached, this);
290 // this->cancelledNav2ZClientConnection_ =
291 // client_->onAborted(&WaypointNavigator::onGoalCancelled, this);
292 // this->abortedNav2ZClientConnection_ =
293 // client_->onCancelled(&WaypointNavigator::onGoalAborted, this);
294 // }
295
296 // Set up navigation result handling
297 if (!succeddedNav2ZClientConnection_.connected())
298 {
305 }
306
307 return nav2ActionInterface_->sendGoal(goal);
308 }
309 else
310 {
311 RCLCPP_WARN(
312 getLogger(),
313 "[CpWaypointsNavigator] All waypoints were consumed. There is no more waypoints available.");
314 }
315
316 return std::nullopt;
317}
318
320{
321 // when it is the last waypoint post an finalization EOF event
322 if (currentWaypoint_ == (long)waypoints_.size() - 1)
323 {
324 RCLCPP_WARN(getLogger(), "[CpWaypointNavigator] Last waypoint reached, posting EOF event. ");
326 }
327}
328
331{
332 if (r.code == rclcpp_action::ResultCode::SUCCEEDED)
333 {
334 this->onGoalReached(r);
335 }
336 else if (r.code == rclcpp_action::ResultCode::ABORTED)
337 {
338 this->onGoalAborted(r);
339 }
340 else if (r.code == rclcpp_action::ResultCode::CANCELED)
341 {
342 this->onGoalCancelled(r);
343 }
344 else
345 {
346 this->onGoalAborted(r);
347 }
348}
349
350void CpWaypointNavigatorBase::insertWaypoint(int index, geometry_msgs::msg::Pose & newpose)
351{
352 if (index >= 0 && index <= (int)waypoints_.size())
353 {
354 waypoints_.insert(waypoints_.begin(), index, newpose);
355 }
356}
357
358void CpWaypointNavigatorBase::setWaypoints(const std::vector<geometry_msgs::msg::Pose> & waypoints)
359{
360 this->waypoints_ = waypoints;
361}
362
363void CpWaypointNavigatorBase::setWaypoints(const std::vector<Pose2D> & waypoints)
364{
365 waypoints_.clear();
366 waypointsNames_.clear();
367 int i = 0;
368 for (auto & p : waypoints)
369 {
370 geometry_msgs::msg::Pose pose;
371 pose.position.x = p.x_;
372 pose.position.y = p.y_;
373 pose.position.z = 0.0;
374 tf2::Quaternion q;
375 q.setRPY(0, 0, p.yaw_);
376 pose.orientation = tf2::toMsg(q);
377
378 waypoints_.push_back(pose);
379 waypointsNames_.push_back(std::to_string(i++));
380 }
381}
382
384{
385 if (index >= 0 && index < (int)waypoints_.size())
386 {
387 waypoints_.erase(waypoints_.begin() + index);
388 }
389}
390
391const std::vector<geometry_msgs::msg::Pose> & CpWaypointNavigatorBase::getWaypoints() const
392{
393 return waypoints_;
394}
395
396geometry_msgs::msg::Pose CpWaypointNavigatorBase::getPose(int index) const
397{
398 if (index >= 0 && index < (int)waypoints_.size())
399 {
400 return waypoints_[index];
401 }
402 else
403 {
404 throw std::out_of_range("Waypoint index out of range");
405 }
406}
407geometry_msgs::msg::Pose CpWaypointNavigatorBase::getCurrentPose() const
408{
409 if (currentWaypoint_ >= 0 && currentWaypoint_ < (int)waypoints_.size())
410 {
412 }
413 else
414 {
415 throw std::out_of_range("Waypoint index out of range");
416 }
417}
418
419std::optional<geometry_msgs::msg::Pose> CpWaypointNavigatorBase::getNamedPose(
420 std::string name) const
421{
422 if (this->waypointsNames_.size() > 0)
423 {
424 for (int i = 0; i < (int)this->waypointsNames_.size(); i++)
425 {
426 if (this->waypointsNames_[i] == name)
427 {
428 return this->waypoints_[i];
429 }
430 }
431 }
432
433 return std::nullopt;
434}
435
436const std::vector<std::string> & CpWaypointNavigatorBase::getWaypointNames() const
437{
438 return waypointsNames_;
439}
440
441std::optional<std::string> CpWaypointNavigatorBase::getCurrentWaypointName() const
442{
443 if (currentWaypoint_ >= 0 && currentWaypoint_ < (int)waypointsNames_.size())
444 {
446 }
447 return std::nullopt;
448}
449
451
452#define HAVE_NEW_YAMLCPP
454{
455 RCLCPP_INFO_STREAM(getLogger(), "[CpWaypointNavigatorBase] Loading file:" << filepath);
456 this->waypoints_.clear();
457 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
458 if (ifs.good() == false)
459 {
460 throw std::string("Waypoints file not found");
461 }
462
463 try
464 {
465#ifdef HAVE_NEW_YAMLCPP
466 YAML::Node node = YAML::Load(ifs);
467#else
468 YAML::Parser parser(ifs);
469 parser.GetNextDocument(node);
470#endif
471
472#ifdef HAVE_NEW_YAMLCPP
473 const YAML::Node & wp_node_tmp = node["waypoints"];
474 const YAML::Node * wp_node = wp_node_tmp ? &wp_node_tmp : NULL;
475#else
476 const YAML::Node * wp_node = node.FindValue("waypoints");
477#endif
478
479 if (wp_node != NULL)
480 {
481 for (std::size_t i = 0; i < wp_node->size(); ++i)
482 {
483 // Parse waypoint entries on YAML
484 geometry_msgs::msg::Pose wp;
485
486 try
487 {
488 // (*wp_node)[i]["name"] >> wp.name;
489 // (*wp_node)[i]["frame_id"] >> wp.header.frame_id;
490
491 auto wpnodei = (*wp_node)[i];
492 wp.position.x = wpnodei["position"]["x"].as<double>();
493 wp.position.y = wpnodei["position"]["y"].as<double>();
494 wp.position.z = wpnodei["position"]["z"].as<double>();
495 wp.orientation.x = wpnodei["orientation"]["x"].as<double>();
496 wp.orientation.y = wpnodei["orientation"]["y"].as<double>();
497 wp.orientation.z = wpnodei["orientation"]["z"].as<double>();
498 wp.orientation.w = wpnodei["orientation"]["w"].as<double>();
499
500 if (wpnodei["name"].IsDefined())
501 {
502 this->waypointsNames_.push_back(wpnodei["name"].as<std::string>());
503 }
504
505 this->waypoints_.push_back(wp);
506 }
507 catch (...)
508 {
509 RCLCPP_ERROR(getLogger(), "parsing waypoint file, syntax error in point %ld", i);
510 }
511 }
512 RCLCPP_INFO_STREAM(getLogger(), "Parsed " << this->waypoints_.size() << " waypoints.");
513 }
514 else
515 {
516 RCLCPP_WARN_STREAM(getLogger(), "Couldn't find any waypoints in the provided yaml file.");
517 }
518 }
519 catch (const YAML::ParserException & ex)
520 {
521 RCLCPP_ERROR_STREAM(
522 getLogger(), "Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
523 }
524}
525
527{
528 RCLCPP_INFO_STREAM(getLogger(), "[CpWaypointNavigator] Loading file:" << filepath);
529 this->waypoints_.clear();
530 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
531 if (ifs.good() == false)
532 {
533 throw std::string("Waypoints file not found");
534 }
535
536 try
537 {
538#ifdef HAVE_NEW_YAMLCPP
539 YAML::Node node = YAML::Load(ifs);
540#else
541 YAML::Parser parser(ifs);
542 parser.GetNextDocument(node);
543#endif
544
545#ifdef HAVE_NEW_YAMLCPP
546 const YAML::Node & wp_node_tmp = node["waypoints"];
547 const YAML::Node * wp_node = wp_node_tmp ? &wp_node_tmp : NULL;
548#else
549 const YAML::Node * wp_node = node.FindValue("waypoints");
550#endif
551
552 if (wp_node != NULL)
553 {
554 for (std::size_t i = 0; i < wp_node->size(); ++i)
555 {
556 // Parse waypoint entries on YAML
557 geometry_msgs::msg::Pose wp;
558
559 try
560 {
561 // (*wp_node)[i]["name"] >> wp.name;
562 // (*wp_node)[i]["frame_id"] >> wp.header.frame_id;
563 wp.position.x = (*wp_node)[i]["x"].as<double>();
564 wp.position.y = (*wp_node)[i]["y"].as<double>();
565 auto name = (*wp_node)[i]["name"].as<std::string>();
566
567 this->waypoints_.push_back(wp);
568 this->waypointsNames_.push_back(name);
569 }
570 catch (...)
571 {
572 RCLCPP_ERROR(getLogger(), "parsing waypoint file, syntax error in point %ld", i);
573 }
574 }
575 RCLCPP_INFO_STREAM(getLogger(), "Parsed " << this->waypoints_.size() << " waypoints.");
576 }
577 else
578 {
579 RCLCPP_WARN_STREAM(getLogger(), "Couldn't find any waypoints in the provided yaml file.");
580 }
581 }
582 catch (const YAML::ParserException & ex)
583 {
584 RCLCPP_ERROR_STREAM(
585 getLogger(), "Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
586 }
587}
588} // namespace cl_nav2z
void setGoalCheckerId(std::string goal_checker_id)
void setDefaultPlanners(bool commit=true)
geometry_msgs::msg::Pose toPoseMsg()
Definition cp_pose.hpp:57
const std::string & getReferenceFrame() const
Definition cp_pose.hpp:79
void setWaypoints(const std::vector< geometry_msgs::msg::Pose > &waypoints)
const std::vector< geometry_msgs::msg::Pose > & getWaypoints() const
void loadWayPointsFromFile2(std::string filepath)
std::vector< geometry_msgs::msg::Pose > waypoints_
geometry_msgs::msg::Pose getCurrentPose() const
void loadWayPointsFromFile(std::string filepath)
std::optional< std::string > getCurrentWaypointName() const
std::optional< geometry_msgs::msg::Pose > getNamedPose(std::string name) const
geometry_msgs::msg::Pose getPose(int index) const
const std::vector< std::string > & getWaypointNames() const
void loadWaypointsFromYamlParameter(std::string parameter_name, std::string yaml_file_package_name)
void insertWaypoint(int index, geometry_msgs::msg::Pose &newpose)
void onGoalReached(const components::CpNav2ActionInterface::WrappedResult &res)
void onGoalAborted(const components::CpNav2ActionInterface::WrappedResult &)
boost::signals2::connection succeddedNav2ZClientConnection_
boost::signals2::connection abortedNav2ZClientConnection_
components::CpNav2ActionInterface * nav2ActionInterface_
smacc2::SmaccSignal< void()> onNavigationRequestCancelled
boost::signals2::connection cancelledNav2ZClientConnection_
void onNavigationResult(const components::CpNav2ActionInterface::WrappedResult &r)
void onGoalCancelled(const components::CpNav2ActionInterface::WrappedResult &)
std::optional< std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > > sendNextGoal(std::optional< NavigateNextWaypointOptions > options=std::nullopt)
smacc2::SmaccSignal< void()> onNavigationRequestAborted
smacc2::SmaccSignal< void()> onNavigationRequestSucceded
boost::signals2::connection onNavigationCancelled(void(T::*callback)(const WrappedResult &), T *object)
boost::signals2::connection onNavigationSucceeded(void(T::*callback)(const WrappedResult &), T *object)
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)
boost::signals2::connection onNavigationAborted(void(T::*callback)(const WrappedResult &), T *object)
void setWorkingMode(WorkingMode workingMode)
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
ISmaccStateMachine * getStateMachine()
ISmaccClient * owner_
Definition component.hpp:88
virtual std::string getName() const
rclcpp::Logger getLogger() const
void requiresComponent(TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
rclcpp::Node::SharedPtr getNode()
virtual std::string getName()=0