SMACC2
Loading...
Searching...
No Matches
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
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
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 ()
 
 CpWaypointNavigatorBase ()
 
virtual ~CpWaypointNavigatorBase ()
 
void onInitialize () override
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
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)
 
void insertWaypoint (int index, geometry_msgs::msg::Pose &newpose)
 
void removeWaypoint (int index)
 
- Protected Member Functions inherited from smacc2::ISmaccComponent
template<typename TOrthogonal , typename TClient >
void onComponentInitialization ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist)
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingNamedComponent (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() [1/2]

cl_nav2z::CpWaypointNavigatorBase::CpWaypointNavigatorBase ( )

◆ ~CpWaypointNavigatorBase() [1/2]

cl_nav2z::CpWaypointNavigatorBase::~CpWaypointNavigatorBase ( )
virtual

Definition at line 42 of file cp_waypoints_navigator.cpp.

42{}

◆ CpWaypointNavigatorBase() [2/2]

cl_nav2z::CpWaypointNavigatorBase::CpWaypointNavigatorBase ( )

◆ ~CpWaypointNavigatorBase() [2/2]

virtual cl_nav2z::CpWaypointNavigatorBase::~CpWaypointNavigatorBase ( )
virtual

Member Function Documentation

◆ forward() [1/2]

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

Definition at line 90 of file cp_waypoints_navigator.cpp.

91{
93 if (currentWaypoint_ >= (long)waypoints_.size() - 1)
94 currentWaypoint_ = (long)waypoints_.size() - 1;
95}

References currentWaypoint_, and waypoints_.

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

Here is the caller graph for this function:

◆ forward() [2/2]

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

◆ getCurrentPose() [1/2]

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

Definition at line 407 of file cp_waypoints_navigator.cpp.

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}

References currentWaypoint_, and waypoints_.

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

Here is the caller graph for this function:

◆ getCurrentPose() [2/2]

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

◆ getCurrentWaypointIndex() [1/2]

◆ getCurrentWaypointIndex() [2/2]

long cl_nav2z::CpWaypointNavigatorBase::getCurrentWaypointIndex ( ) const

◆ getCurrentWaypointName() [1/2]

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

◆ getCurrentWaypointName() [2/2]

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

◆ getNamedPose() [1/2]

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

Definition at line 419 of file cp_waypoints_navigator.cpp.

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}

References waypoints_, and waypointsNames_.

◆ getNamedPose() [2/2]

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

◆ getPose() [1/2]

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

Definition at line 396 of file cp_waypoints_navigator.cpp.

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}

References waypoints_.

◆ getPose() [2/2]

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

◆ getWaypointNames() [1/2]

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

Definition at line 436 of file cp_waypoints_navigator.cpp.

437{
438 return waypointsNames_;
439}

References waypointsNames_.

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

Here is the caller graph for this function:

◆ getWaypointNames() [2/2]

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

◆ getWaypoints() [1/2]

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

Definition at line 391 of file cp_waypoints_navigator.cpp.

392{
393 return waypoints_;
394}

References waypoints_.

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

Here is the caller graph for this function:

◆ getWaypoints() [2/2]

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

◆ insertWaypoint() [1/2]

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

Definition at line 350 of file cp_waypoints_navigator.cpp.

351{
352 if (index >= 0 && index <= (int)waypoints_.size())
353 {
354 waypoints_.insert(waypoints_.begin(), index, newpose);
355 }
356}

References waypoints_.

◆ insertWaypoint() [2/2]

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

◆ loadWayPointsFromFile() [1/2]

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

Definition at line 453 of file cp_waypoints_navigator.cpp.

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 (int64_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}
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:

◆ loadWayPointsFromFile() [2/2]

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

◆ loadWayPointsFromFile2() [1/2]

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

Definition at line 526 of file cp_waypoints_navigator.cpp.

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 (int64_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}

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

Here is the call graph for this function:

◆ loadWayPointsFromFile2() [2/2]

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

◆ loadWaypointsFromYamlParameter() [1/2]

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

Definition at line 160 of file cp_waypoints_navigator.cpp.

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}
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:

◆ loadWaypointsFromYamlParameter() [2/2]

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

◆ notifyGoalReached() [1/2]

void cl_nav2z::CpWaypointNavigatorBase::notifyGoalReached ( )

Definition at line 319 of file cp_waypoints_navigator.cpp.

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}

References currentWaypoint_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::postEvent(), 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:

◆ notifyGoalReached() [2/2]

void cl_nav2z::CpWaypointNavigatorBase::notifyGoalReached ( )

◆ onInitialize() [1/2]

void cl_nav2z::CpWaypointNavigatorBase::onInitialize ( )
overridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 46 of file cp_waypoints_navigator.cpp.

46{}

◆ onInitialize() [2/2]

void cl_nav2z::CpWaypointNavigatorBase::onInitialize ( )
overridevirtual

Reimplemented from smacc2::ISmaccComponent.

◆ onOrthogonalAllocation()

template<typename TOrthogonal , typename TSourceObject >
void cl_nav2z::CpWaypointNavigatorBase::onOrthogonalAllocation ( )
inline

Definition at line 65 of file cp_waypoints_navigator_base.hpp.

66 {
67 // Call the new method to maintain functionality for third-party inheritors
69 }

References onStateOrthogonalAllocation().

Here is the call graph for this function:

◆ onStateOrthogonalAllocation() [1/2]

template<typename TOrthogonal , typename TSourceObject >
void cl_nav2z::CpWaypointNavigatorBase::onStateOrthogonalAllocation ( )
inline

Definition at line 59 of file cp_waypoints_navigator_base.hpp.

60 {
61 ClNav2Z * client = dynamic_cast<ClNav2Z *>(owner_);
62 waypointsEventDispatcher.initialize<TSourceObject, TOrthogonal>(client);
63 }
namespace cl_nav2z class ClNav2Z
ISmaccClient * owner_

References WaypointEventDispatcher::initialize(), smacc2::ISmaccComponent::owner_, and waypointsEventDispatcher.

Referenced by onOrthogonalAllocation().

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

◆ onStateOrthogonalAllocation() [2/2]

template<typename TOrthogonal , typename TSourceObject >
void cl_nav2z::CpWaypointNavigatorBase::onStateOrthogonalAllocation ( )
inline

Definition at line 72 of file cp_waypoints_navigator_base.hpp.

73 {
74 ClNav2Z * client = dynamic_cast<ClNav2Z *>(owner_);
75 waypointsEventDispatcher.initialize<TSourceObject, TOrthogonal>(client);
76 }

References WaypointEventDispatcher::initialize(), smacc2::ISmaccComponent::owner_, and waypointsEventDispatcher.

Here is the call graph for this function:

◆ removeWaypoint() [1/2]

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

Definition at line 383 of file cp_waypoints_navigator.cpp.

384{
385 if (index >= 0 && index < (int)waypoints_.size())
386 {
387 waypoints_.erase(waypoints_.begin() + index);
388 }
389}

References waypoints_.

◆ removeWaypoint() [2/2]

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

◆ rewind() [1/2]

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

Definition at line 84 of file cp_waypoints_navigator.cpp.

85{
88}

References currentWaypoint_.

◆ rewind() [2/2]

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

◆ seekName() [1/2]

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

Definition at line 97 of file cp_waypoints_navigator.cpp.

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}

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:

◆ seekName() [2/2]

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

◆ setWaypoints() [1/4]

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

Definition at line 358 of file cp_waypoints_navigator.cpp.

359{
360 this->waypoints_ = waypoints;
361}

References waypoints_.

◆ setWaypoints() [2/4]

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

◆ setWaypoints() [3/4]

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

Definition at line 363 of file cp_waypoints_navigator.cpp.

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}

References waypoints_, and waypointsNames_.

◆ setWaypoints() [4/4]

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

Member Data Documentation

◆ currentWaypoint_

◆ waypoints_

◆ waypointsEventDispatcher

◆ waypointsNames_

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

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