25 target(INVALID_NUM,INVALID_NUM),
26 target_heading(INVALID_NUM),
27 target_frame_id(
"map"),
28 allowed_distance(INVALID_NUM),
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_)
57 else s+=
"target=(**Coordinates not set!!**) ";
61 else s+=
" (heading: any) ";
65 else s+=
" (**allowed_distance not set!!**) ";
67 s+= (
allow_skip ?
" allow_skip: YES" :
" allow_skip: NO ");
97 counter_seen_reachable(0)
102 TWaypoint::operator =(wp);
116 final_goal_reached(false),
117 waypoint_index_current_goal(-1),
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)),
152 unsigned int idx = 0;
156 p.allow_skip ?
params.outter_radius :
params.outter_radius_non_skippable,
157 p.allow_skip ?
params.inner_radius :
params.inner_radius_non_skippable,
159 gl_pt->setLocation(
p.target.x,
p.target.y, 0.01);
160 gl_pt->setColor_u8(
params.color_regular);
164 gl_pt->enableShowName(
true);
182 unsigned int idx = 0;
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),
192 gl_pt->setLocation(
p.target.x,
p.target.y, 0.01);
195 gl_pt->setName(
mrpt::format(
"WayPt #%2u Reach:%s", idx,
p.reached ?
"YES" :
"NO"));
196 gl_pt->enableShowName(
true);
198 gl_pt->setColor_u8(is_cur_goal ?
params.color_current_goal : (
p.reached ?
params.color_reached :
params.color_regular));
215 c.write(
s,
"waypoint_count", N);
219 for (
unsigned int i = 0; i < N; i++)
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);
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);
237 const unsigned int N =
c.read_int(
s,
"waypoint_count", 0,
true);
240 for (
unsigned int i = 0; i < N; i++)
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);
251 wp.speed_ratio =
c.read_double(
s,
mrpt::format(
"wp%03u_speed_ratio", i), 1.0,
false);
void load(const mrpt::utils::CConfigFileBase &c, const std::string &s)
Loads waypoints to a config file section.
bool allow_skip
[Default=true] Whether it is allowed to the navigator to proceed to a more advanced waypoint in the s...
std::string getAsText() const
Gets navigation params as a human-readable format.
static CArrowPtr Create()
A set of object, which are referenced to the coordinates framework established in this object...
bool isValid() const
Check whether all the minimum mandatory fields have been filled by the user.
TWaypointSequence()
Ctor with default values.
static const double INVALID_NUM
The default value of fields (used to detect non-set values)
void save(mrpt::utils::CConfigFileBase &c, const std::string &s) const
Saves waypoints to a config file section.
std::string getAsText() const
get in human-readable format
used in getAsOpenglVisualization()
void getAsOpenglVisualization(mrpt::opengl::CSetOfObjects &obj, const mrpt::nav::TWaypointsRenderingParams ¶ms=mrpt::nav::TWaypointsRenderingParams()) const
Renders the sequence of waypoints (previous contents of obj are cleared)
std::vector< TWaypoint > waypoints
A single waypoint within TWaypointSequence.
GLsizei GLsizei GLuint * obj
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...
double RAD2DEG(const double x)
Radians to degrees.
TWaypoint()
Ctor with default values.
TWaypointsRenderingParams()
A waypoint with an execution status.
bool final_goal_reached
Whether the final waypoint has been reached successfuly.
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
GLsizei const GLchar ** string
void getAsOpenglVisualization(mrpt::opengl::CSetOfObjects &obj, const mrpt::nav::TWaypointsRenderingParams ¶ms=mrpt::nav::TWaypointsRenderingParams()) const
Renders the sequence of waypoints (previous contents of obj are cleared)
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
TWaypointStatus & operator=(const TWaypoint &wp)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
TWaypointStatusSequence()
Ctor with default values.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
mrpt::math::TPoint2D target
[Must be set by the user] Coordinates of desired target location (world/global coordinates).
std::string getAsText() const
Gets navigation params as a human-readable format.
double target_heading
[Default=any heading] Optionally, set to the desired orientation [radians] of the robot at this waypo...
double allowed_distance
[Must be set by the user] How close should the robot get to this waypoint for it to be considered rea...
std::string getAsText() const
Gets navigation params as a human-readable format.
std::vector< TWaypointStatus > waypoints
Waypoints parameters and status (reached, skipped, etc.)
int waypoint_index_current_goal
Index in waypoints of the waypoint the navigator is currently trying to reach.
GLenum const GLfloat * params
double speed_ratio
(Default=1.0) Desired robot speed at the target, as a ratio of the full robot speed.