SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
cl_nav2z::CpWaypointNavigatorBase Class Reference

#include <cp_waypoints_navigator_base.hpp>

Inheritance diagram for cl_nav2z::CpWaypointNavigatorBase:
Inheritance graph
Collaboration diagram for cl_nav2z::CpWaypointNavigatorBase:
Collaboration graph

Public Member Functions

 CpWaypointNavigatorBase ()
 
virtual ~CpWaypointNavigatorBase ()
 
void onInitialize () override
 
void loadWayPointsFromFile (std::string filepath)
 
void loadWayPointsFromFile2 (std::string filepath)
 
void setWaypoints (const std::vector< geometry_msgs::msg::Pose > &waypoints)
 
void setWaypoints (const std::vector< Pose2D > &waypoints)
 
const std::vector< geometry_msgs::msg::Pose > & getWaypoints () const
 
const std::vector< std::string > & getWaypointNames () const
 
std::optional< geometry_msgs::msg::Pose > getNamedPose (std::string name) const
 
geometry_msgs::msg::Pose getPose (int index) const
 
geometry_msgs::msg::Pose getCurrentPose () const
 
long getCurrentWaypointIndex () const
 
std::optional< std::string > getCurrentWaypointName () const
 
void rewind (int count)
 
void forward (int count)
 
void seekName (std::string name)
 
void loadWaypointsFromYamlParameter (std::string parameter_name, std::string yaml_file_package_name)
 
void notifyGoalReached ()
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Public Attributes

WaypointEventDispatcher waypointsEventDispatcher
 
long currentWaypoint_
 

Protected Member Functions

void insertWaypoint (int index, geometry_msgs::msg::Pose &newpose)
 
void removeWaypoint (int index)
 
- Protected Member Functions inherited from smacc2::ISmaccComponent
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentTypecreateSiblingComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentTypecreateSiblingNamedComponent (std::string name, TArgs... targs)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger () const
 
ISmaccStateMachinegetStateMachine ()
 

Protected Attributes

std::vector< geometry_msgs::msg::Pose > waypoints_
 
std::vector< std::string > waypointsNames_
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Definition at line 47 of file cp_waypoints_navigator_base.hpp.

Constructor & Destructor Documentation

◆ CpWaypointNavigatorBase()

cl_nav2z::CpWaypointNavigatorBase::CpWaypointNavigatorBase ( )

◆ ~CpWaypointNavigatorBase()

cl_nav2z::CpWaypointNavigatorBase::~CpWaypointNavigatorBase ( )
virtual

Definition at line 40 of file cp_waypoints_navigator.cpp.

40{}

Member Function Documentation

◆ forward()

void cl_nav2z::CpWaypointNavigatorBase::forward ( int  count)

Definition at line 82 of file cp_waypoints_navigator.cpp.

83{
85 if (currentWaypoint_ >= (long)waypoints_.size() - 1)
86 currentWaypoint_ = (long)waypoints_.size() - 1;
87}

References currentWaypoint_, and waypoints_.

Referenced by cl_nav2z::CbSeekWaypoint::onEntry(), and cl_nav2z::CbNavigateNextWaypointFree::onSucessCallback().

Here is the caller graph for this function:

◆ getCurrentPose()

geometry_msgs::msg::Pose cl_nav2z::CpWaypointNavigatorBase::getCurrentPose ( ) const

Definition at line 385 of file cp_waypoints_navigator.cpp.

386{
387 if (currentWaypoint_ >= 0 && currentWaypoint_ < (int)waypoints_.size())
388 {
390 }
391 else
392 {
393 throw std::out_of_range("Waypoint index out of range");
394 }
395}

References currentWaypoint_, and waypoints_.

Referenced by cl_nav2z::CbNavigateNextWaypointFree::onEntry().

Here is the caller graph for this function:

◆ getCurrentWaypointIndex()

long cl_nav2z::CpWaypointNavigatorBase::getCurrentWaypointIndex ( ) const

◆ getCurrentWaypointName()

std::optional< std::string > cl_nav2z::CpWaypointNavigatorBase::getCurrentWaypointName ( ) const

Definition at line 419 of file cp_waypoints_navigator.cpp.

420{
421 if (currentWaypoint_ >= 0 && currentWaypoint_ < (int)waypointsNames_.size())
422 {
424 }
425 return std::nullopt;
426}

References currentWaypoint_, and waypointsNames_.

Referenced by cl_nav2z::CbNavigateNextWaypoint::onEntry(), and cl_nav2z::CbNavigateNextWaypointUntilReached::onNavigationActionSuccess().

Here is the caller graph for this function:

◆ getNamedPose()

std::optional< geometry_msgs::msg::Pose > cl_nav2z::CpWaypointNavigatorBase::getNamedPose ( std::string  name) const

Definition at line 397 of file cp_waypoints_navigator.cpp.

399{
400 if (this->waypointsNames_.size() > 0)
401 {
402 for (int i = 0; i < (int)this->waypointsNames_.size(); i++)
403 {
404 if (this->waypointsNames_[i] == name)
405 {
406 return this->waypoints_[i];
407 }
408 }
409 }
410
411 return std::nullopt;
412}

References waypoints_, and waypointsNames_.

◆ getPose()

geometry_msgs::msg::Pose cl_nav2z::CpWaypointNavigatorBase::getPose ( int  index) const

Definition at line 374 of file cp_waypoints_navigator.cpp.

375{
376 if (index >= 0 && index < (int)waypoints_.size())
377 {
378 return waypoints_[index];
379 }
380 else
381 {
382 throw std::out_of_range("Waypoint index out of range");
383 }
384}

References waypoints_.

◆ getWaypointNames()

const std::vector< std::string > & cl_nav2z::CpWaypointNavigatorBase::getWaypointNames ( ) const

Definition at line 414 of file cp_waypoints_navigator.cpp.

415{
416 return waypointsNames_;
417}

References waypointsNames_.

Referenced by cl_nav2z::CpWaypointsVisualizer::onInitialize().

Here is the caller graph for this function:

◆ getWaypoints()

const std::vector< geometry_msgs::msg::Pose > & cl_nav2z::CpWaypointNavigatorBase::getWaypoints ( ) const

Definition at line 369 of file cp_waypoints_navigator.cpp.

370{
371 return waypoints_;
372}

References waypoints_.

Referenced by cl_nav2z::CpWaypointsVisualizer::onInitialize().

Here is the caller graph for this function:

◆ insertWaypoint()

void cl_nav2z::CpWaypointNavigatorBase::insertWaypoint ( int  index,
geometry_msgs::msg::Pose &  newpose 
)
protected

Definition at line 328 of file cp_waypoints_navigator.cpp.

329{
330 if (index >= 0 && index <= (int)waypoints_.size())
331 {
332 waypoints_.insert(waypoints_.begin(), index, newpose);
333 }
334}

References waypoints_.

◆ loadWayPointsFromFile()

void cl_nav2z::CpWaypointNavigatorBase::loadWayPointsFromFile ( std::string  filepath)

Definition at line 431 of file cp_waypoints_navigator.cpp.

432{
433 RCLCPP_INFO_STREAM(getLogger(), "[CpWaypointNavigatorBase] Loading file:" << filepath);
434 this->waypoints_.clear();
435 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
436 if (ifs.good() == false)
437 {
438 throw std::string("Waypoints file not found");
439 }
440
441 try
442 {
443#ifdef HAVE_NEW_YAMLCPP
444 YAML::Node node = YAML::Load(ifs);
445#else
446 YAML::Parser parser(ifs);
447 parser.GetNextDocument(node);
448#endif
449
450#ifdef HAVE_NEW_YAMLCPP
451 const YAML::Node & wp_node_tmp = node["waypoints"];
452 const YAML::Node * wp_node = wp_node_tmp ? &wp_node_tmp : NULL;
453#else
454 const YAML::Node * wp_node = node.FindValue("waypoints");
455#endif
456
457 if (wp_node != NULL)
458 {
459 for (int64_t i = 0; i < wp_node->size(); ++i)
460 {
461 // Parse waypoint entries on YAML
462 geometry_msgs::msg::Pose wp;
463
464 try
465 {
466 // (*wp_node)[i]["name"] >> wp.name;
467 // (*wp_node)[i]["frame_id"] >> wp.header.frame_id;
468
469 auto wpnodei = (*wp_node)[i];
470 wp.position.x = wpnodei["position"]["x"].as<double>();
471 wp.position.y = wpnodei["position"]["y"].as<double>();
472 wp.position.z = wpnodei["position"]["z"].as<double>();
473 wp.orientation.x = wpnodei["orientation"]["x"].as<double>();
474 wp.orientation.y = wpnodei["orientation"]["y"].as<double>();
475 wp.orientation.z = wpnodei["orientation"]["z"].as<double>();
476 wp.orientation.w = wpnodei["orientation"]["w"].as<double>();
477
478 if (wpnodei["name"].IsDefined())
479 {
480 this->waypointsNames_.push_back(wpnodei["name"].as<std::string>());
481 }
482
483 this->waypoints_.push_back(wp);
484 }
485 catch (...)
486 {
487 RCLCPP_ERROR(getLogger(), "parsing waypoint file, syntax error in point %ld", i);
488 }
489 }
490 RCLCPP_INFO_STREAM(getLogger(), "Parsed " << this->waypoints_.size() << " waypoints.");
491 }
492 else
493 {
494 RCLCPP_WARN_STREAM(getLogger(), "Couldn't find any waypoints in the provided yaml file.");
495 }
496 }
497 catch (const YAML::ParserException & ex)
498 {
499 RCLCPP_ERROR_STREAM(
500 getLogger(), "Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
501 }
502}
rclcpp::Logger getLogger() const

References smacc2::ISmaccComponent::getLogger(), waypoints_, and waypointsNames_.

Referenced by loadWaypointsFromYamlParameter(), and cl_nav2z::CbLoadWaypointsFile::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadWayPointsFromFile2()

void cl_nav2z::CpWaypointNavigatorBase::loadWayPointsFromFile2 ( std::string  filepath)

Definition at line 504 of file cp_waypoints_navigator.cpp.

505{
506 RCLCPP_INFO_STREAM(getLogger(), "[CpWaypointNavigator] Loading file:" << filepath);
507 this->waypoints_.clear();
508 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
509 if (ifs.good() == false)
510 {
511 throw std::string("Waypoints file not found");
512 }
513
514 try
515 {
516#ifdef HAVE_NEW_YAMLCPP
517 YAML::Node node = YAML::Load(ifs);
518#else
519 YAML::Parser parser(ifs);
520 parser.GetNextDocument(node);
521#endif
522
523#ifdef HAVE_NEW_YAMLCPP
524 const YAML::Node & wp_node_tmp = node["waypoints"];
525 const YAML::Node * wp_node = wp_node_tmp ? &wp_node_tmp : NULL;
526#else
527 const YAML::Node * wp_node = node.FindValue("waypoints");
528#endif
529
530 if (wp_node != NULL)
531 {
532 for (int64_t i = 0; i < wp_node->size(); ++i)
533 {
534 // Parse waypoint entries on YAML
535 geometry_msgs::msg::Pose wp;
536
537 try
538 {
539 // (*wp_node)[i]["name"] >> wp.name;
540 // (*wp_node)[i]["frame_id"] >> wp.header.frame_id;
541 wp.position.x = (*wp_node)[i]["x"].as<double>();
542 wp.position.y = (*wp_node)[i]["y"].as<double>();
543 auto name = (*wp_node)[i]["name"].as<std::string>();
544
545 this->waypoints_.push_back(wp);
546 this->waypointsNames_.push_back(name);
547 }
548 catch (...)
549 {
550 RCLCPP_ERROR(getLogger(), "parsing waypoint file, syntax error in point %ld", i);
551 }
552 }
553 RCLCPP_INFO_STREAM(getLogger(), "Parsed " << this->waypoints_.size() << " waypoints.");
554 }
555 else
556 {
557 RCLCPP_WARN_STREAM(getLogger(), "Couldn't find any waypoints in the provided yaml file.");
558 }
559 }
560 catch (const YAML::ParserException & ex)
561 {
562 RCLCPP_ERROR_STREAM(
563 getLogger(), "Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
564 }
565}

References smacc2::ISmaccComponent::getLogger(), waypoints_, and waypointsNames_.

Here is the call graph for this function:

◆ loadWaypointsFromYamlParameter()

void cl_nav2z::CpWaypointNavigatorBase::loadWaypointsFromYamlParameter ( std::string  parameter_name,
std::string  yaml_file_package_name 
)

Definition at line 152 of file cp_waypoints_navigator.cpp.

154{
155 // if it is the first time and the waypoints navigator is not configured
156 std::string planfilepath;
157 planfilepath = getNode()->declare_parameter(parameter_name, planfilepath);
158 RCLCPP_INFO(getLogger(), "waypoints plan parameter: %s", planfilepath.c_str());
159 if (getNode()->get_parameter(parameter_name, planfilepath))
160 {
161 std::string package_share_directory =
162 ament_index_cpp::get_package_share_directory(yaml_file_package_name);
163
164 RCLCPP_INFO(getLogger(), "file macro path: %s", planfilepath.c_str());
165
166 boost::replace_all(planfilepath, "$(pkg_share)", package_share_directory);
167
168 RCLCPP_INFO(getLogger(), "package share path: %s", package_share_directory.c_str());
169 RCLCPP_INFO(getLogger(), "waypoints plan file: %s", planfilepath.c_str());
170
171 this->loadWayPointsFromFile(planfilepath);
172 RCLCPP_INFO(getLogger(), "waypoints plan: %s", planfilepath.c_str());
173 }
174 else
175 {
176 RCLCPP_ERROR(getLogger(), "waypoints plan file not found: NONE");
177 }
178}
void loadWayPointsFromFile(std::string filepath)
rclcpp::Node::SharedPtr getNode()

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), and loadWayPointsFromFile().

Referenced by cl_nav2z::CbLoadWaypointsFile::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ notifyGoalReached()

void cl_nav2z::CpWaypointNavigatorBase::notifyGoalReached ( )

Definition at line 298 of file cp_waypoints_navigator.cpp.

299{
300 // when it is the last waypoint post an finalization EOF event
301 if (currentWaypoint_ == (long)waypoints_.size() - 1)
302 {
303 RCLCPP_WARN(getLogger(), "[CpWaypointNavigator] Last waypoint reached, posting EOF event. ");
304 this->postEvent<EvWaypointFinal>();
305 }
306}

References currentWaypoint_, smacc2::ISmaccComponent::getLogger(), and waypoints_.

Referenced by cl_nav2z::CpWaypointNavigator::onGoalReached(), and cl_nav2z::CbNavigateNextWaypointFree::onSucessCallback().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onInitialize()

void cl_nav2z::CpWaypointNavigatorBase::onInitialize ( )
overridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 44 of file cp_waypoints_navigator.cpp.

44{}

◆ removeWaypoint()

void cl_nav2z::CpWaypointNavigatorBase::removeWaypoint ( int  index)
protected

Definition at line 361 of file cp_waypoints_navigator.cpp.

362{
363 if (index >= 0 && index < (int)waypoints_.size())
364 {
365 waypoints_.erase(waypoints_.begin() + index);
366 }
367}

References waypoints_.

◆ rewind()

void cl_nav2z::CpWaypointNavigatorBase::rewind ( int  count)

Definition at line 76 of file cp_waypoints_navigator.cpp.

77{
80}

References currentWaypoint_.

◆ seekName()

void cl_nav2z::CpWaypointNavigatorBase::seekName ( std::string  name)

Definition at line 89 of file cp_waypoints_navigator.cpp.

90{
91 bool found = false;
92
93 auto previousWaypoint = currentWaypoint_;
94
95 while (!found && currentWaypoint_ < (long)waypoints_.size())
96 {
97 auto & nextName = waypointsNames_[currentWaypoint_];
98 RCLCPP_INFO(
99 getLogger(), "[CpWaypointNavigator] seeking ,%ld/%ld candidate waypoint: %s",
100 currentWaypoint_, waypoints_.size(), nextName.c_str());
101 if (name == nextName)
102 {
103 found = true;
104 RCLCPP_INFO(
105 getLogger(), "[CpWaypointNavigator] found target waypoint: %s == %s-> found",
106 nextName.c_str(), name.c_str());
107 }
108 else
109 {
110 RCLCPP_INFO(
111 getLogger(), "[CpWaypointNavigator] current waypoint: %s != %s -> forward",
112 nextName.c_str(), name.c_str());
114 }
115 }
116
117 if (found)
118 {
119 if (currentWaypoint_ >= (long)waypoints_.size() - 1)
120 currentWaypoint_ = (long)waypoints_.size() - 1;
121 }
122 else // search backwards
123 {
124 currentWaypoint_ = previousWaypoint;
125 while (!found && currentWaypoint_ > 0)
126 {
127 auto & nextName = waypointsNames_[currentWaypoint_];
128 RCLCPP_INFO(
129 getLogger(), "[CpWaypointNavigator] seeking , candidate waypoint: %s", nextName.c_str());
130 if (name == nextName)
131 {
132 found = true;
133 RCLCPP_INFO(
134 getLogger(), "[CpWaypointNavigator] found target waypoint: %s == %s-> found",
135 nextName.c_str(), name.c_str());
136 }
137 else
138 {
139 RCLCPP_INFO(
140 getLogger(), "[CpWaypointNavigator] current waypoint: %s != %s -> rewind",
141 nextName.c_str(), name.c_str());
143 }
144 }
145 }
146
147 RCLCPP_INFO(
148 getLogger(), "[CpWaypointNavigator] seekName( %s), previous index: %ld, after index: %ld",
149 name.c_str(), previousWaypoint, currentWaypoint_);
150}

References currentWaypoint_, smacc2::ISmaccComponent::getLogger(), waypoints_, and waypointsNames_.

Referenced by cl_nav2z::CbNavigateNamedWaypoint::onEntry(), and cl_nav2z::CbSeekWaypoint::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setWaypoints() [1/2]

void cl_nav2z::CpWaypointNavigatorBase::setWaypoints ( const std::vector< geometry_msgs::msg::Pose > &  waypoints)

Definition at line 336 of file cp_waypoints_navigator.cpp.

337{
338 this->waypoints_ = waypoints;
339}

References waypoints_.

◆ setWaypoints() [2/2]

void cl_nav2z::CpWaypointNavigatorBase::setWaypoints ( const std::vector< Pose2D > &  waypoints)

Definition at line 341 of file cp_waypoints_navigator.cpp.

342{
343 waypoints_.clear();
344 waypointsNames_.clear();
345 int i = 0;
346 for (auto & p : waypoints)
347 {
348 geometry_msgs::msg::Pose pose;
349 pose.position.x = p.x_;
350 pose.position.y = p.y_;
351 pose.position.z = 0.0;
352 tf2::Quaternion q;
353 q.setRPY(0, 0, p.yaw_);
354 pose.orientation = tf2::toMsg(q);
355
356 waypoints_.push_back(pose);
357 waypointsNames_.push_back(std::to_string(i++));
358 }
359}

References waypoints_, and waypointsNames_.

Member Data Documentation

◆ currentWaypoint_

long cl_nav2z::CpWaypointNavigatorBase::currentWaypoint_

◆ waypoints_

std::vector<geometry_msgs::msg::Pose> cl_nav2z::CpWaypointNavigatorBase::waypoints_
protected

◆ waypointsEventDispatcher

WaypointEventDispatcher cl_nav2z::CpWaypointNavigatorBase::waypointsEventDispatcher

◆ waypointsNames_

std::vector<std::string> cl_nav2z::CpWaypointNavigatorBase::waypointsNames_
protected

The documentation for this class was generated from the following files: