SMACC
Loading...
Searching...
No Matches
waypoints_navigator.cpp
Go to the documentation of this file.
6
7#include <fstream>
8#include <ros/ros.h>
9#include <yaml-cpp/yaml.h>
10#include <tf/transform_datatypes.h>
11
12namespace cl_move_base_z
13{
15 : currentWaypoint_(0),
16 waypoints_(0)
17{
18}
19
21{
22 client_ = dynamic_cast<ClMoveBaseZ *>(owner_);
23}
24
26{
29 this->succeddedConnection_.disconnect();
30}
31
33{
34 if (currentWaypoint_ >= 0 && currentWaypoint_ < waypoints_.size())
35 {
36 auto &next = waypoints_[currentWaypoint_];
37
40 auto pose = p->toPoseMsg();
41
42 ClMoveBaseZ::Goal goal;
43 goal.target_pose.header.frame_id = p->getReferenceFrame();
44 goal.target_pose.header.stamp = ros::Time::now();
45 goal.target_pose.pose = next;
46
47 auto plannerSwitcher = client_->getComponent<PlannerSwitcher>();
48 plannerSwitcher->setDefaultPlanners();
49
50 ros::spinOnce();
51 ros::Duration(5).sleep();
52
53 if (odomTracker != nullptr)
54 {
55 odomTracker->pushPath("FreeNavigationToGoalWaypointPose");
56 odomTracker->setStartPoint(pose);
58 }
59
61 client_->sendGoal(goal);
62 }
63 else
64 {
65 ROS_WARN("[WaypointsNavigator] All waypoints were consumed. There is no more waypoints available.");
66 }
67}
68
69void WaypointNavigator::insertWaypoint(int index, geometry_msgs::Pose &newpose)
70{
71 if (index >= 0 && index <= waypoints_.size())
72 {
73 waypoints_.insert(waypoints_.begin(), index, newpose);
74 }
75}
76
77void WaypointNavigator::setWaypoints(const std::vector<geometry_msgs::Pose> &waypoints)
78{
79 this->waypoints_ = waypoints;
80}
81
82void WaypointNavigator::setWaypoints(const std::vector<Pose2D> &waypoints)
83{
84 this->waypoints_.clear();
85 for (auto &p : waypoints)
86 {
87 geometry_msgs::Pose pose;
88 pose.position.x = p.x_;
89 pose.position.y = p.y_;
90 pose.position.z = 0.0;
91 pose.orientation = tf::createQuaternionMsgFromYaw(p.yaw_);
92
93 this->waypoints_.push_back(pose);
94 }
95}
96
98{
99 if (index >= 0 && index < waypoints_.size())
100 {
101 waypoints_.erase(waypoints_.begin() + index);
102 }
103}
104
105const std::vector<geometry_msgs::Pose> &WaypointNavigator::getWaypoints() const
106{
107 return waypoints_;
108}
109
111{
112 return currentWaypoint_;
113}
114
115#define HAVE_NEW_YAMLCPP
117{
118 this->waypoints_.clear();
119 std::ifstream ifs(filepath.c_str(), std::ifstream::in);
120 if (ifs.good() == false)
121 {
122 throw std::string("Waypoints file not found");
123 }
124
125 try
126 {
127
128#ifdef HAVE_NEW_YAMLCPP
129 YAML::Node node = YAML::Load(ifs);
130#else
131 YAML::Parser parser(ifs);
132 parser.GetNextDocument(node);
133#endif
134
135#ifdef HAVE_NEW_YAMLCPP
136 const YAML::Node &wp_node_tmp = node["waypoints"];
137 const YAML::Node *wp_node = wp_node_tmp ? &wp_node_tmp : NULL;
138#else
139 const YAML::Node *wp_node = node.FindValue("waypoints");
140#endif
141
142 if (wp_node != NULL)
143 {
144 for (uint64_t i = 0; i < wp_node->size(); ++i)
145 {
146 // Parse waypoint entries on YAML
147 geometry_msgs::Pose wp;
148
149 try
150 {
151 // (*wp_node)[i]["name"] >> wp.name;
152 // (*wp_node)[i]["frame_id"] >> wp.header.frame_id;
153 wp.position.x = (*wp_node)[i]["position"]["x"].as<double>();
154 wp.position.y = (*wp_node)[i]["position"]["y"].as<double>();
155 wp.position.z = (*wp_node)[i]["position"]["z"].as<double>();
156 wp.orientation.x = (*wp_node)[i]["orientation"]["x"].as<double>();
157 wp.orientation.y = (*wp_node)[i]["orientation"]["y"].as<double>();
158 wp.orientation.z = (*wp_node)[i]["orientation"]["z"].as<double>();
159 wp.orientation.w = (*wp_node)[i]["orientation"]["w"].as<double>();
160
161 this->waypoints_.push_back(wp);
162 }
163 catch (...)
164 {
165 ROS_ERROR("parsing waypoint file, syntax error in point %d", i);
166 }
167 }
168 ROS_INFO_STREAM("Parsed " << this->waypoints_.size() << " waypoints.");
169 }
170 else
171 {
172 ROS_WARN_STREAM("Couldn't find any waypoints in the provided yaml file.");
173 }
174 }
175 catch (const YAML::ParserException &ex)
176 {
177 ROS_ERROR_STREAM("Error loading the Waypoints YAML file. Incorrect syntax: " << ex.what());
178 }
179}
180} // namespace cl_move_base_z
SmaccActionClientBase< move_base_msgs::MoveBaseAction >::ResultConstPtr ResultConstPtr
void loadWayPointsFromFile(std::string filepath)
void setWaypoints(const std::vector< geometry_msgs::Pose > &waypoints)
WaypointEventDispatcher waypointsEventDispatcher
const std::vector< geometry_msgs::Pose > & getWaypoints() const
void insertWaypoint(int index, geometry_msgs::Pose &newpose)
boost::signals2::connection succeddedConnection_
std::vector< geometry_msgs::Pose > waypoints_
void onGoalReached(ClMoveBaseZ::ResultConstPtr &res)
This class track the required distance of the cord based on the external localization system.
Definition: odom_tracker.h:47
TComponent * getComponent()
ISmaccClient * owner_
Definition: component.h:57
boost::signals2::connection onSucceeded(void(T::*callback)(ResultConstPtr &), T *object)