21#include <tf2/transform_datatypes.h>
22#include <yaml-cpp/yaml.h>
24#include <ament_index_cpp/get_package_share_directory.hpp>
33#include <rclcpp/rclcpp.hpp>
37using namespace std::chrono_literals;
75 getLogger(),
"[CpWaypointNavigator] Goal result received, incrementing waypoint index: %ld",
107 getLogger(),
"[CpWaypointNavigator] seeking ,%ld/%ld candidate waypoint: %s",
109 if (name == nextName)
113 getLogger(),
"[CpWaypointNavigator] found target waypoint: %s == %s-> found",
114 nextName.c_str(), name.c_str());
119 getLogger(),
"[CpWaypointNavigator] current waypoint: %s != %s -> forward",
120 nextName.c_str(), name.c_str());
137 getLogger(),
"[CpWaypointNavigator] seeking , candidate waypoint: %s", nextName.c_str());
138 if (name == nextName)
142 getLogger(),
"[CpWaypointNavigator] found target waypoint: %s == %s-> found",
143 nextName.c_str(), name.c_str());
148 getLogger(),
"[CpWaypointNavigator] current waypoint: %s != %s -> rewind",
149 nextName.c_str(), name.c_str());
156 getLogger(),
"[CpWaypointNavigator] seekName( %s), previous index: %ld, after index: %ld",
161 std::string parameter_name, std::string yaml_file_package_name)
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))
169 std::string package_share_directory =
170 ament_index_cpp::get_package_share_directory(yaml_file_package_name);
172 RCLCPP_INFO(
getLogger(),
"file macro path: %s", planfilepath.c_str());
174 boost::replace_all(planfilepath,
"$(pkg_share)", package_share_directory);
176 RCLCPP_INFO(
getLogger(),
"package share path: %s", package_share_directory.c_str());
177 RCLCPP_INFO(
getLogger(),
"waypoints plan file: %s", planfilepath.c_str());
180 RCLCPP_INFO(
getLogger(),
"waypoints plan: %s", planfilepath.c_str());
184 RCLCPP_ERROR(
getLogger(),
"waypoints plan file not found: NONE");
198std::optional<std::shared_future<
199 std::shared_ptr<rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose>>>>
206 std::string nextName;
211 getLogger(),
"[CpWaypointNavigator] sending goal, waypoint: %s", nextName.c_str());
219 nav2_msgs::action::NavigateToPose::Goal goal;
227 goal.pose.pose = next;
233 if (options && options->controllerName_)
236 getLogger(),
"[WaypointsNavigator] override controller: %s",
237 options->controllerName_->c_str());
243 RCLCPP_WARN(
getLogger(),
"[WaypointsNavigator] Configuring default planners");
250 if (options && options->goalCheckerName_)
253 getLogger(),
"[WaypointsNavigator] override goal checker: %s",
254 options->goalCheckerName_->c_str());
260 RCLCPP_WARN(
getLogger(),
"[WaypointsNavigator] Configuring default goal checker");
269 RCLCPP_INFO(
getLogger(),
"[WaypointsNavigator] Getting odom tracker");
274 if (odomTracker !=
nullptr)
276 RCLCPP_INFO(
getLogger(),
"[WaypointsNavigator] Storing path in odom tracker");
313 "[CpWaypointsNavigator] All waypoints were consumed. There is no more waypoints available.");
324 RCLCPP_WARN(
getLogger(),
"[CpWaypointNavigator] Last waypoint reached, posting EOF event. ");
332 if (r.code == rclcpp_action::ResultCode::SUCCEEDED)
336 else if (r.code == rclcpp_action::ResultCode::ABORTED)
340 else if (r.code == rclcpp_action::ResultCode::CANCELED)
352 if (index >= 0 && index <= (
int)
waypoints_.size())
368 for (
auto & p : waypoints)
370 geometry_msgs::msg::Pose pose;
371 pose.position.x = p.x_;
372 pose.position.y = p.y_;
373 pose.position.z = 0.0;
375 q.setRPY(0, 0, p.yaw_);
376 pose.orientation = tf2::toMsg(q);
385 if (index >= 0 && index < (
int)
waypoints_.size())
398 if (index >= 0 && index < (
int)
waypoints_.size())
404 throw std::out_of_range(
"Waypoint index out of range");
415 throw std::out_of_range(
"Waypoint index out of range");
420 std::string name)
const
452#define HAVE_NEW_YAMLCPP
455 RCLCPP_INFO_STREAM(
getLogger(),
"[CpWaypointNavigatorBase] Loading file:" << filepath);
457 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
458 if (ifs.good() ==
false)
460 throw std::string(
"Waypoints file not found");
465#ifdef HAVE_NEW_YAMLCPP
466 YAML::Node node = YAML::Load(ifs);
468 YAML::Parser parser(ifs);
469 parser.GetNextDocument(node);
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;
476 const YAML::Node * wp_node = node.FindValue(
"waypoints");
481 for (std::size_t i = 0; i < wp_node->size(); ++i)
484 geometry_msgs::msg::Pose wp;
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>();
500 if (wpnodei[
"name"].IsDefined())
509 RCLCPP_ERROR(
getLogger(),
"parsing waypoint file, syntax error in point %ld", i);
516 RCLCPP_WARN_STREAM(
getLogger(),
"Couldn't find any waypoints in the provided yaml file.");
519 catch (
const YAML::ParserException & ex)
522 getLogger(),
"Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
528 RCLCPP_INFO_STREAM(
getLogger(),
"[CpWaypointNavigator] Loading file:" << filepath);
530 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
531 if (ifs.good() ==
false)
533 throw std::string(
"Waypoints file not found");
538#ifdef HAVE_NEW_YAMLCPP
539 YAML::Node node = YAML::Load(ifs);
541 YAML::Parser parser(ifs);
542 parser.GetNextDocument(node);
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;
549 const YAML::Node * wp_node = node.FindValue(
"waypoints");
554 for (std::size_t i = 0; i < wp_node->size(); ++i)
557 geometry_msgs::msg::Pose wp;
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>();
572 RCLCPP_ERROR(
getLogger(),
"parsing waypoint file, syntax error in point %ld", i);
579 RCLCPP_WARN_STREAM(
getLogger(),
"Couldn't find any waypoints in the provided yaml file.");
582 catch (
const YAML::ParserException & ex)
585 getLogger(),
"Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
void postWaypointEvent(int index)
void setGoalCheckerId(std::string goal_checker_id)
void setDefaultPlanners(bool commit=true)
void setDesiredController(std::string)
geometry_msgs::msg::Pose toPoseMsg()
const std::string & getReferenceFrame() const
void setWaypoints(const std::vector< geometry_msgs::msg::Pose > &waypoints)
const std::vector< geometry_msgs::msg::Pose > & getWaypoints() const
void loadWayPointsFromFile2(std::string filepath)
void seekName(std::string name)
CpWaypointNavigatorBase()
std::vector< geometry_msgs::msg::Pose > waypoints_
std::vector< std::string > waypointsNames_
geometry_msgs::msg::Pose getCurrentPose() const
void loadWayPointsFromFile(std::string filepath)
virtual ~CpWaypointNavigatorBase()
std::optional< std::string > getCurrentWaypointName() const
std::optional< geometry_msgs::msg::Pose > getNamedPose(std::string name) const
WaypointEventDispatcher waypointsEventDispatcher
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 removeWaypoint(int index)
void insertWaypoint(int index, geometry_msgs::msg::Pose &newpose)
long getCurrentWaypointIndex() const
void onInitialize() override
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 onInitialize() override
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)
typename GoalHandle::WrappedResult WrappedResult
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()
virtual std::string getName() const
rclcpp::Logger getLogger() const
void requiresComponent(TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
rclcpp::Node::SharedPtr getNode()
ISmaccState * getCurrentState() const
virtual std::string getName()=0