21#include <tf2/transform_datatypes.h>
22#include <yaml-cpp/yaml.h>
32#include <rclcpp/rclcpp.hpp>
36using namespace std::chrono_literals;
60 getLogger(),
"[WaypointNavigator] Goal result received, incrementing waypoint index: %ld",
96 getLogger(),
"[WaypointNavigator] found target waypoint: %s == %s-> found",
97 nextName.c_str(), name.c_str());
102 getLogger(),
"[WaypointNavigator] current waypoint: %s != %s -> forward", nextName.c_str(),
120 getLogger(),
"[WaypointNavigator] seeking , candidate waypoint: %s", nextName.c_str());
121 if (name == nextName)
125 getLogger(),
"[WaypointNavigator] found target waypoint: %s == %s-> found",
126 nextName.c_str(), name.c_str());
131 getLogger(),
"[WaypointNavigator] current waypoint: %s != %s -> rewind", nextName.c_str(),
139 getLogger(),
"[WaypointNavigator] seekName( %s), previous index: %ld, after index: %ld",
153std::optional<std::shared_future<
154 std::shared_ptr<rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose>>>>
156 std::optional<NavigateNextWaypointOptions> options,
163 std::string nextName;
167 RCLCPP_INFO(
getLogger(),
"[WaypointNavigator] sending goal, waypoint: %s", nextName.c_str());
179 goal.pose.header.frame_id = p->getReferenceFrame();
181 goal.pose.pose = next;
185 if (options && options->controllerName_)
188 getLogger(),
"[WaypointsNavigator] override controller: %s",
189 options->controllerName_->c_str());
191 plannerSwitcher->setDesiredController(*options->controllerName_);
195 RCLCPP_WARN(
getLogger(),
"[WaypointsNavigator] Configuring default planners");
200 if (options && options->goalCheckerName_)
203 getLogger(),
"[WaypointsNavigator] override goal checker: %s",
204 options->goalCheckerName_->c_str());
206 goalCheckerSwitcher->setGoalCheckerId(*options->goalCheckerName_);
210 RCLCPP_WARN(
getLogger(),
"[WaypointsNavigator] Configuring default goal checker");
211 goalCheckerSwitcher->setGoalCheckerId(
"goal_checker");
214 plannerSwitcher->commitPublish();
219 RCLCPP_INFO(
getLogger(),
"[WaypointsNavigator] Getting odom tracker");
221 if (odomTracker !=
nullptr)
223 RCLCPP_INFO(
getLogger(),
"[WaypointsNavigator] Storing path in odom tracker");
227 odomTracker->pushPath(pathname);
228 odomTracker->setStartPoint(pose);
243 auto callbackptr = resultCallback.lock();
254 "[WaypointsNavigator] All waypoints were consumed. There is no more waypoints available.");
262 if (r.code == rclcpp_action::ResultCode::SUCCEEDED)
266 else if (r.code == rclcpp_action::ResultCode::ABORTED)
270 else if (r.code == rclcpp_action::ResultCode::CANCELED)
282 if (index >= 0 && index <= (
int)
waypoints_.size())
298 for (
auto & p : waypoints)
300 geometry_msgs::msg::Pose pose;
301 pose.position.x = p.x_;
302 pose.position.y = p.y_;
303 pose.position.z = 0.0;
305 q.setRPY(0, 0, p.yaw_);
306 pose.orientation = tf2::toMsg(q);
315 if (index >= 0 && index < (
int)
waypoints_.size())
358#define HAVE_NEW_YAMLCPP
361 RCLCPP_INFO_STREAM(
getLogger(),
"[WaypointNavigator] Loading file:" << filepath);
363 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
364 if (ifs.good() ==
false)
366 throw std::string(
"Waypoints file not found");
371#ifdef HAVE_NEW_YAMLCPP
372 YAML::Node node = YAML::Load(ifs);
374 YAML::Parser parser(ifs);
375 parser.GetNextDocument(node);
378#ifdef HAVE_NEW_YAMLCPP
379 const YAML::Node & wp_node_tmp = node[
"waypoints"];
380 const YAML::Node * wp_node = wp_node_tmp ? &wp_node_tmp : NULL;
382 const YAML::Node * wp_node = node.FindValue(
"waypoints");
387 for (uint64_t i = 0; i < wp_node->size(); ++i)
390 geometry_msgs::msg::Pose wp;
397 auto wpnodei = (*wp_node)[i];
398 wp.position.x = wpnodei[
"position"][
"x"].as<
double>();
399 wp.position.y = wpnodei[
"position"][
"y"].as<
double>();
400 wp.position.z = wpnodei[
"position"][
"z"].as<
double>();
401 wp.orientation.x = wpnodei[
"orientation"][
"x"].as<
double>();
402 wp.orientation.y = wpnodei[
"orientation"][
"y"].as<
double>();
403 wp.orientation.z = wpnodei[
"orientation"][
"z"].as<
double>();
404 wp.orientation.w = wpnodei[
"orientation"][
"w"].as<
double>();
406 if (wpnodei[
"name"].IsDefined())
415 RCLCPP_ERROR(
getLogger(),
"parsing waypoint file, syntax error in point %ld", i);
422 RCLCPP_WARN_STREAM(
getLogger(),
"Couldn't find any waypoints in the provided yaml file.");
425 catch (
const YAML::ParserException & ex)
428 getLogger(),
"Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
434 RCLCPP_INFO_STREAM(
getLogger(),
"[WaypointNavigator] Loading file:" << filepath);
436 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
437 if (ifs.good() ==
false)
439 throw std::string(
"Waypoints file not found");
444#ifdef HAVE_NEW_YAMLCPP
445 YAML::Node node = YAML::Load(ifs);
447 YAML::Parser parser(ifs);
448 parser.GetNextDocument(node);
451#ifdef HAVE_NEW_YAMLCPP
452 const YAML::Node & wp_node_tmp = node[
"waypoints"];
453 const YAML::Node * wp_node = wp_node_tmp ? &wp_node_tmp : NULL;
455 const YAML::Node * wp_node = node.FindValue(
"waypoints");
460 for (uint64_t i = 0; i < wp_node->size(); ++i)
463 geometry_msgs::msg::Pose wp;
469 wp.position.x = (*wp_node)[i][
"x"].as<
double>();
470 wp.position.y = (*wp_node)[i][
"y"].as<
double>();
471 auto name = (*wp_node)[i][
"name"].as<std::string>();
478 RCLCPP_ERROR(
getLogger(),
"parsing waypoint file, syntax error in point %ld", i);
485 RCLCPP_WARN_STREAM(
getLogger(),
"Couldn't find any waypoints in the provided yaml file.");
488 catch (
const YAML::ParserException & ex)
491 getLogger(),
"Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
void setDefaultPlanners(bool commit=true)
geometry_msgs::msg::Pose toPoseMsg()
void postWaypointEvent(int index)
boost::signals2::connection cancelledNav2ZClientConnection_
void loadWayPointsFromFile2(std::string filepath)
void onGoalCancelled(const ClNav2Z::WrappedResult &)
std::optional< geometry_msgs::msg::Pose > getNamedPose(std::string name) const
const std::vector< geometry_msgs::msg::Pose > & getWaypoints() const
long getCurrentWaypointIndex() const
boost::signals2::connection abortedNav2ZClientConnection_
std::vector< std::string > waypointsNames_
void removeWaypoint(int index)
void onNavigationResult(const ClNav2Z::WrappedResult &r)
WaypointEventDispatcher waypointsEventDispatcher
boost::signals2::connection succeddedNav2ZClientConnection_
smacc2::SmaccSignal< void()> onNavigationRequestCancelled
void onGoalReached(const ClNav2Z::WrappedResult &res)
std::optional< std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > > sendNextGoal(std::optional< NavigateNextWaypointOptions > options=std::nullopt, cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::WeakPtr callback=cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::WeakPtr())
smacc2::SmaccSignal< void()> onNavigationRequestAborted
std::vector< geometry_msgs::msg::Pose > waypoints_
void onInitialize() override
void seekName(std::string name)
void loadWayPointsFromFile(std::string filepath)
const std::vector< std::string > & getWaypointNames() const
std::optional< std::string > getCurrentWaypointName() const
void onGoalAborted(const ClNav2Z::WrappedResult &)
smacc2::SmaccSignal< void()> onNavigationRequestSucceded
void setWaypoints(const std::vector< geometry_msgs::msg::Pose > &waypoints)
void insertWaypoint(int index, geometry_msgs::msg::Pose &newpose)
ISmaccStateMachine * getStateMachine()
TComponent * getComponent()
ISmaccStateMachine * getStateMachine()
virtual std::string getName() const
rclcpp::Logger getLogger() const
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
ISmaccState * getCurrentState() const
virtual std::string getName()=0
std::weak_ptr< SmaccSignal< void(const WrappedResult &), optional_last_value< typename boost::function_traits< void(const WrappedResult &) >::result_type >, int, std::less< int >, function< void(const WrappedResult &) >, typename extended_signature< function_traits< void(const WrappedResult &) >::arity, void(const WrappedResult &) >::function_type, boost::signals2::mutex > > WeakPtr
typename ActionClient::Goal Goal
GoalHandle::WrappedResult WrappedResult
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal, typename SmaccActionResultSignal::WeakPtr resultCallback=typename SmaccActionResultSignal::WeakPtr())