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



Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020