Main MRPT website > C++ reference for MRPT 1.5.7
TWaypoint.cpp
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 
10 #include "nav-precomp.h" // Precomp header
11 
14 #include <mrpt/opengl/CDisk.h>
15 #include <mrpt/opengl/CArrow.h>
16 #include <limits>
17 
18 using namespace mrpt::nav;
19 using namespace std;
20 
21 const double TWaypoint::INVALID_NUM = std::numeric_limits<double>::max();
22 
23 // TWaypoint ==========
25  target(INVALID_NUM,INVALID_NUM),
26  target_heading(INVALID_NUM),
27  target_frame_id("map"),
28  allowed_distance(INVALID_NUM),
29  speed_ratio(1.0),
30  allow_skip(true)
31 {
32 }
33 
34 TWaypoint::TWaypoint(double target_x, double target_y, double allowed_distance_, bool allow_skip_, double target_heading_, double speed_ratio_) :
35  target(target_x,target_y),
36  target_heading(target_heading_),
37  target_frame_id("map"),
38  allowed_distance(allowed_distance_),
39  speed_ratio(speed_ratio_),
40  allow_skip(allow_skip_)
41 {
42 }
43 
44 bool TWaypoint::isValid() const
45 {
46  return
47  (target.x!=INVALID_NUM) &&
48  (target.y!=INVALID_NUM) &&
50 }
51 
53 {
54  std::string s;
56  s+=mrpt::format("target=(%8.03f,%8.03f) ",target.x,target.y);
57  else s+="target=(**Coordinates not set!!**) ";
58 
61  else s+=" (heading: any) ";
62 
64  s+=mrpt::format("allowed_dist=%8.03f ",allowed_distance);
65  else s+=" (**allowed_distance not set!!**) ";
66 
67  s+= (allow_skip ? " allow_skip: YES" : " allow_skip: NO ");
68  s+= mrpt::format(" speed_ratio: %.01f", speed_ratio);
69  return s;
70 }
71 
72 
73 // TWaypointSequence ==========
75 {
76 }
77 
78 // Gets navigation params as a human-readable format:
80 {
81  string s;
82  s+=mrpt::format("List of %u waypoints:\n", static_cast<unsigned int>(waypoints.size()) );
83  unsigned int i=0;
84  for (const auto &wp : waypoints) {
85  s+= mrpt::format(" #%3u: ",i++);
86  s+= wp.getAsText();
87  s+= "\n";
88  }
89  return s;
90 }
91 
92 // TWaypointStatus ==========
94  reached(false),
95  skipped(false),
96  timestamp_reach(INVALID_TIMESTAMP),
97  counter_seen_reachable(0)
98 {
99 }
101 {
102  TWaypoint::operator =(wp);
103  return *this;
104 }
106 {
108  s += mrpt::format(" reached=%s", (reached ? "YES":"NO ") );;
109  return s;
110 }
111 
112 // TWaypointStatusSequence ======
114  waypoints(),
115  timestamp_nav_started(INVALID_TIMESTAMP),
116  final_goal_reached(false),
117  waypoint_index_current_goal(-1),
118  last_robot_pose(TWaypoint::INVALID_NUM,TWaypoint::INVALID_NUM,TWaypoint::INVALID_NUM)
119 {
120 }
121 
123 {
124  string s;
125  s+=mrpt::format("Status for %u waypoints:\n", static_cast<unsigned int>(waypoints.size()) );
126  unsigned int i=0;
127  for (const auto &wp : waypoints) {
128  s+= mrpt::format(" #%3u: ",i++);
129  s+= wp.getAsText();
130  s+= "\n";
131  }
132  s+=mrpt::format(" final_goal_reached:%s waypoint_index_current_goal=%d\n", (final_goal_reached ? "YES":"NO "), waypoint_index_current_goal );
133  return s;
134 }
135 
137  outter_radius(.3), inner_radius(.2),
138  outter_radius_non_skippable(.3), inner_radius_non_skippable(.0),
139  outter_radius_reached(.2), inner_radius_reached(.1),
140  heading_arrow_len(1.0),
141  color_regular(mrpt::utils::TColor(0x00, 0x00, 0xff)),
142  color_current_goal(mrpt::utils::TColor(0xff, 0x00, 0x20)),
143  color_reached(mrpt::utils::TColor(0x00, 0x00, 0xc0,0xd0)),
144  show_labels(true)
145 {
146 }
147 
148 
150 {
151  obj.clear();
152  unsigned int idx = 0;
153  for (const auto &p : waypoints)
154  {
155  auto gl_pt = mrpt::opengl::CDisk::Create(
156  p.allow_skip ? params.outter_radius : params.outter_radius_non_skippable,
157  p.allow_skip ? params.inner_radius : params.inner_radius_non_skippable,
158  15);
159  gl_pt->setLocation(p.target.x, p.target.y, 0.01);
160  gl_pt->setColor_u8(params.color_regular);
161  if (params.show_labels)
162  {
163  gl_pt->setName(mrpt::format("WayPt #%2u", idx));
164  gl_pt->enableShowName(true);
165  }
166  obj.insert(gl_pt);
167 
168  if (p.target_heading != TWaypoint::INVALID_NUM)
169  {
170  auto o = mrpt::opengl::CArrow::Create(0, 0, 0, params.heading_arrow_len, 0.0f, 0.0f);
171  o->setPose(mrpt::poses::CPose3D(p.target.x, p.target.y, 0.02, p.target_heading, 0, 0));
172  obj.insert(o);
173  }
174  ++idx;
175  }
176 }
177 
179 {
180  obj.clear();
181  {
182  unsigned int idx = 0;
183  for (const auto &p : waypoints)
184  {
185  const bool is_cur_goal = (int(idx) == waypoint_index_current_goal);
186 
187  mrpt::opengl::CDiskPtr gl_pt = mrpt::opengl::CDisk::Create(
188  p.reached ? params.outter_radius_reached : (p.allow_skip ? params.outter_radius : params.outter_radius_non_skippable),
189  p.reached ? params.inner_radius_reached : (p.allow_skip ? params.inner_radius : params.inner_radius_non_skippable),
190  15
191  );
192  gl_pt->setLocation(p.target.x, p.target.y, 0.01);
193  if (params.show_labels)
194  {
195  gl_pt->setName(mrpt::format("WayPt #%2u Reach:%s", idx, p.reached ? "YES" : "NO"));
196  gl_pt->enableShowName(true);
197  }
198  gl_pt->setColor_u8(is_cur_goal ? params.color_current_goal : (p.reached ? params.color_reached : params.color_regular));
199  obj.insert(gl_pt);
200 
201  if (p.target_heading != TWaypoint::INVALID_NUM)
202  {
203  auto o = mrpt::opengl::CArrow::Create(0, 0, 0, params.heading_arrow_len, 0.0f, 0.0f);
204  o->setPose(mrpt::poses::CPose3D(p.target.x, p.target.y, 0.02, p.target_heading, 0, 0));
205  obj.insert(o);
206  }
207  ++idx;
208  }
209  }
210 }
211 
213 {
214  const unsigned int N = waypoints.size();
215  c.write(s, "waypoint_count", N);
216 
217  const int NP = 27; // name padding
218 
219  for (unsigned int i = 0; i < N; i++)
220  {
221  const auto &wp = waypoints[i];
222 
223  c.write(s, mrpt::format("wp%03u_allowed_distance", i), wp.allowed_distance, NP);
224  c.write(s, mrpt::format("wp%03u_allow_skip", i), wp.allow_skip, NP);
225  c.write(s, mrpt::format("wp%03u_target_x", i), wp.target.x, NP);
226  c.write(s, mrpt::format("wp%03u_target_y", i), wp.target.y, NP);
227  c.write(s, mrpt::format("wp%03u_target_frame_id", i), wp.target_frame_id, NP);
228  c.write(s, mrpt::format("wp%03u_target_heading", i), wp.target_heading, NP);
229  c.write(s, mrpt::format("wp%03u_speed_ratio", i), wp.speed_ratio, NP);
230  }
231 }
232 
234 {
235  this->clear();
236 
237  const unsigned int N = c.read_int(s, "waypoint_count", 0, true);
238  waypoints.resize(N);
239 
240  for (unsigned int i = 0; i < N; i++)
241  {
242  auto &wp = waypoints[i];
243 
244  wp.allowed_distance = c.read_double(s, mrpt::format("wp%03u_allowed_distance", i), 0, true);
245  wp.allow_skip = c.read_bool(s, mrpt::format("wp%03u_allow_skip", i), true, true);
246  wp.target.x = c.read_double(s, mrpt::format("wp%03u_target_x", i), 0, true);
247  wp.target.y = c.read_double(s, mrpt::format("wp%03u_target_y", i), 0, true);
248  wp.target_frame_id = c.read_string(s, mrpt::format("wp%03u_target_frame_id", i), "map", false);
249  double hd = c.read_double(s, mrpt::format("wp%03u_target_heading", i), mrpt::nav::TWaypoint::INVALID_NUM);
250  wp.target_heading = (hd > 100) ? mrpt::nav::TWaypoint::INVALID_NUM : hd;
251  wp.speed_ratio = c.read_double(s, mrpt::format("wp%03u_speed_ratio", i), 1.0, false);
252  }
253 }
void load(const mrpt::utils::CConfigFileBase &c, const std::string &s)
Loads waypoints to a config file section.
Definition: TWaypoint.cpp:233
bool allow_skip
[Default=true] Whether it is allowed to the navigator to proceed to a more advanced waypoint in the s...
Definition: TWaypoint.h:51
double y
X,Y coordinates.
std::string getAsText() const
Gets navigation params as a human-readable format.
Definition: TWaypoint.cpp:105
static CArrowPtr Create()
A set of object, which are referenced to the coordinates framework established in this object...
Definition: CSetOfObjects.h:32
bool isValid() const
Check whether all the minimum mandatory fields have been filled by the user.
Definition: TWaypoint.cpp:44
TWaypointSequence()
Ctor with default values.
Definition: TWaypoint.cpp:74
static const double INVALID_NUM
The default value of fields (used to detect non-set values)
Definition: TWaypoint.h:58
void save(mrpt::utils::CConfigFileBase &c, const std::string &s) const
Saves waypoints to a config file section.
Definition: TWaypoint.cpp:212
std::string getAsText() const
get in human-readable format
Definition: TWaypoint.cpp:52
used in getAsOpenglVisualization()
Definition: TWaypoint.h:62
void getAsOpenglVisualization(mrpt::opengl::CSetOfObjects &obj, const mrpt::nav::TWaypointsRenderingParams &params=mrpt::nav::TWaypointsRenderingParams()) const
Renders the sequence of waypoints (previous contents of obj are cleared)
Definition: TWaypoint.cpp:178
std::vector< TWaypoint > waypoints
Definition: TWaypoint.h:80
A single waypoint within TWaypointSequence.
Definition: TWaypoint.h:25
STL namespace.
GLdouble s
Definition: glext.h:3602
GLsizei GLsizei GLuint * obj
Definition: glext.h:3902
This class allows loading and storing values and vectors of different types from a configuration text...
bool reached
Whether this waypoint has been reached already (to within the allowed distance as per user specificat...
Definition: TWaypoint.h:97
static CDiskPtr Create()
double RAD2DEG(const double x)
Radians to degrees.
TWaypoint()
Ctor with default values.
Definition: TWaypoint.cpp:24
const GLubyte * c
Definition: glext.h:5590
A waypoint with an execution status.
Definition: TWaypoint.h:95
bool final_goal_reached
Whether the final waypoint has been reached successfuly.
Definition: TWaypoint.h:114
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
GLsizei const GLchar ** string
Definition: glext.h:3919
void getAsOpenglVisualization(mrpt::opengl::CSetOfObjects &obj, const mrpt::nav::TWaypointsRenderingParams &params=mrpt::nav::TWaypointsRenderingParams()) const
Renders the sequence of waypoints (previous contents of obj are cleared)
Definition: TWaypoint.cpp:149
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Definition: datetime.h:17
TWaypointStatus & operator=(const TWaypoint &wp)
Definition: TWaypoint.cpp:100
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
TWaypointStatusSequence()
Ctor with default values.
Definition: TWaypoint.cpp:113
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:72
mrpt::math::TPoint2D target
[Must be set by the user] Coordinates of desired target location (world/global coordinates).
Definition: TWaypoint.h:29
std::string getAsText() const
Gets navigation params as a human-readable format.
Definition: TWaypoint.cpp:79
double target_heading
[Default=any heading] Optionally, set to the desired orientation [radians] of the robot at this waypo...
Definition: TWaypoint.h:33
double allowed_distance
[Must be set by the user] How close should the robot get to this waypoint for it to be considered rea...
Definition: TWaypoint.h:37
std::string getAsText() const
Gets navigation params as a human-readable format.
Definition: TWaypoint.cpp:122
std::vector< TWaypointStatus > waypoints
Waypoints parameters and status (reached, skipped, etc.)
Definition: TWaypoint.h:112
int waypoint_index_current_goal
Index in waypoints of the waypoint the navigator is currently trying to reach.
Definition: TWaypoint.h:118
GLfloat GLfloat p
Definition: glext.h:5587
GLenum const GLfloat * params
Definition: glext.h:3514
double speed_ratio
(Default=1.0) Desired robot speed at the target, as a ratio of the full robot speed.
Definition: TWaypoint.h:44



Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019