YARP
Yet Another Robot Platform
navigation2DServer.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  *
4  * This library is free software; you can redistribute it and/or
5  * modify it under the terms of the GNU Lesser General Public
6  * License as published by the Free Software Foundation; either
7  * version 2.1 of the License, or (at your option) any later version.
8  *
9  * This library is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12  * Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public
15  * License along with this library; if not, write to the Free Software
16  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
17  */
18 
19 #define _USE_MATH_DEFINES
20 
21 #include <yarp/os/Network.h>
22 #include <yarp/os/RFModule.h>
23 #include <yarp/os/Time.h>
24 #include <yarp/os/Port.h>
25 #include <yarp/os/LogComponent.h>
26 #include <yarp/os/LogStream.h>
28 #include <yarp/dev/INavigation2D.h>
29 #include <yarp/dev/MapGrid2D.h>
30 #include <math.h>
31 #include <cmath>
32 #include "navigation2DServer.h"
33 
34 using namespace yarp::os;
35 using namespace yarp::dev;
36 using namespace yarp::dev::Nav2D;
37 using namespace std;
38 
39 namespace {
40 YARP_LOG_COMPONENT(NAVIGATION2DSERVER, "yarp.device.navigation2DServer")
41 }
42 
43 #ifndef RAD2DEG
44 #define RAD2DEG 180.0/M_PI
45 #endif
46 
48 {
49  iNav_target = nullptr;
50  iNav_ctrl = nullptr;
52 }
53 
55 {
56  if (device2attach.size() != 1)
57  {
58  yCError(NAVIGATION2DSERVER, "Cannot attach more than one device");
59  return false;
60  }
61 
62  yarp::dev::PolyDriver * Idevice2attach = device2attach[0]->poly;
63 
64  if (Idevice2attach->isValid())
65  {
66  Idevice2attach->view(iNav_target);
67  Idevice2attach->view(iNav_ctrl);
68  }
69 
70  if (nullptr == iNav_target ||
71  nullptr == iNav_ctrl)
72  {
73  yCError(NAVIGATION2DSERVER, "Subdevice passed to attach method is invalid");
74  return false;
75  }
76 
77  PeriodicThread::setPeriod(m_period);
78  return PeriodicThread::start();
79 }
80 
82 {
83  if (PeriodicThread::isRunning())
84  {
85  PeriodicThread::stop();
86  }
87  iNav_target = nullptr;
88  iNav_ctrl = nullptr;
89  return true;
90 }
91 
93 {
94  Property params;
95  params.fromString(config.toString().c_str());
96  yCDebug(NAVIGATION2DSERVER) << "Configuration: \n" << config.toString().c_str();
97 
98  if (!config.check("period"))
99  {
100  yCInfo(NAVIGATION2DSERVER) << "Missing 'period' parameter. Using default value: 0.010";
101  m_period = 0.010;
102  }
103  else
104  {
105  m_period = config.find("period").asFloat64();
106  }
107 
108  string local_name = "/navigationServer";
109  if (!config.check("name"))
110  {
111  yCInfo(NAVIGATION2DSERVER) << "Missing 'name' parameter. Using default value: /navigationServer";
112  }
113  else
114  {
115  local_name = config.find("name").asString();
116  }
117  m_rpcPortName = local_name + "/rpc";
118  m_streamingPortName = local_name + "/streaming:o";
119 
120  if (config.check("subdevice"))
121  {
122  Property p;
123  PolyDriverList driverlist;
124  p.fromString(config.toString(), false);
125  p.put("device", config.find("subdevice").asString());
126 
127  if (!pNav.open(p) || !pNav.isValid())
128  {
129  yCError(NAVIGATION2DSERVER) << "Failed to open subdevice.. check params";
130  return false;
131  }
132 
133  driverlist.push(&pNav, "1");
134  if (!attachAll(driverlist))
135  {
136  yCError(NAVIGATION2DSERVER) << "Failed to open subdevice.. check params";
137  return false;
138  }
139  }
141 
142  if (!initialize_YARP(config))
143  {
144  yCError(NAVIGATION2DSERVER) << "Error initializing YARP ports";
145  return false;
146  }
147 
148  return true;
149 }
150 
152 {
153  if (!m_rpcPort.open(m_rpcPortName.c_str()))
154  {
155  yCError(NAVIGATION2DSERVER, "Failed to open port %s", m_rpcPortName.c_str());
156  return false;
157  }
158  m_rpcPort.setReader(*this);
159  return true;
160 }
161 
163 {
164  yCTrace(NAVIGATION2DSERVER, "Close");
165  if (PeriodicThread::isRunning())
166  {
167  PeriodicThread::stop();
168  }
169 
170  detachAll();
171  return true;
172 }
173 
174 bool navigation2DServer::parse_respond_string(const yarp::os::Bottle& command, yarp::os::Bottle& reply)
175 {
176  if (command.get(0).isString() == false)
177  {
178  yCError(NAVIGATION2DSERVER) << "General error in navigation2DServer::parse_respond_string()";
179  return false;
180  }
181 
182  if (command.get(0).asString() == "help")
183  {
184  reply.addVocab(Vocab::encode("many"));
185  reply.addString("Navigation2DServer does not support rpc commands in plain text format, only vocabs.");
186  reply.addString("Please use the rpc port of Navigation2DClient.");
187  }
188  else
189  {
190  reply.addString("Unknown command. Type 'help'.");
191  }
192  return true;
193 }
194 
195 bool navigation2DServer::parse_respond_vocab(const yarp::os::Bottle& command, yarp::os::Bottle& reply)
196 {
197  if (command.get(0).isVocab() == false)
198  {
199  yCError(NAVIGATION2DSERVER) << "General error in navigation2DServer::parse_respond_vocab()";
200  return false;
201  }
202 
203  if (command.get(0).asVocab() != VOCAB_INAVIGATION ||
204  command.get(1).isVocab() == false)
205  {
206  yCError(NAVIGATION2DSERVER) << "Invalid vocab received";
207  reply.addVocab(VOCAB_ERR);
208  return true;
209  }
210 
211  int request = command.get(1).asVocab();
212  if (request == VOCAB_NAV_GOTOABS)
213  {
214  Map2DLocation loc;
215  loc.map_id = command.get(2).asString();
216  loc.x = command.get(3).asFloat64();
217  loc.y = command.get(4).asFloat64();
218  loc.theta = command.get(5).asFloat64();
220  if (ret)
221  {
222  reply.addVocab(VOCAB_OK);
223  }
224  else
225  {
226  yCError(NAVIGATION2DSERVER) << "gotoTargetByAbsoluteLocation() failed";
227  reply.addVocab(VOCAB_ERR);
228  }
229  }
230  else if (request == VOCAB_NAV_RECOMPUTE_PATH)
231  {
233  if (ret)
234  {
235  reply.addVocab(VOCAB_OK);
236  }
237  else
238  {
239  yCError(NAVIGATION2DSERVER) << "recomputeCurrentNavigationPath() failed";
240  reply.addVocab(VOCAB_ERR);
241  }
242  reply.addVocab(VOCAB_OK);
243  }
244  else if (request == VOCAB_NAV_GOTOREL)
245  {
246  if (command.size() == 5)
247  {
248  double x = command.get(2).asFloat64();
249  double y = command.get(3).asFloat64();
250  double theta = command.get(4).asFloat64();
251  bool ret = iNav_target->gotoTargetByRelativeLocation(x, y, theta);
252  if (ret)
253  {
254  reply.addVocab(VOCAB_OK);
255  }
256  else
257  {
258  yCError(NAVIGATION2DSERVER) << "gotoTargetByRelativeLocation() failed";
259  reply.addVocab(VOCAB_ERR);
260  }
261  }
262  else if (command.size() == 4)
263  {
264  double x = command.get(2).asFloat64();
265  double y = command.get(3).asFloat64();
267  if (ret)
268  {
269  reply.addVocab(VOCAB_OK);
270  }
271  else
272  {
273  yCError(NAVIGATION2DSERVER) << "gotoTargetByRelativeLocation() failed";
274  reply.addVocab(VOCAB_ERR);
275  }
276  }
277  else
278  {
279  yCError(NAVIGATION2DSERVER) << "Invalid number of params";
280  reply.addVocab(VOCAB_ERR);
281  }
282  }
283  else if (request == VOCAB_NAV_VELOCITY_CMD)
284  {
285  double x_vel = command.get(2).asFloat64();
286  double y_vel = command.get(3).asFloat64();
287  double t_vel = command.get(4).asFloat64();
288  double timeout = command.get(5).asFloat64();
289  bool ret = iNav_target->applyVelocityCommand(x_vel,y_vel,t_vel,timeout);
290  if (ret)
291  {
292  reply.addVocab(VOCAB_OK);
293  reply.addInt32(VOCAB_OK);
294  }
295  else
296  {
297  yCError(NAVIGATION2DSERVER) << "applyVelocityCommand() failed";
298  reply.addVocab(VOCAB_ERR);
299  }
300  }
301  else if (request == VOCAB_NAV_GET_NAVIGATION_STATUS)
302  {
304  bool ret = iNav_ctrl->getNavigationStatus(nav_status);
305  if (ret)
306  {
307  reply.addVocab(VOCAB_OK);
308  reply.addInt32(nav_status);
309  }
310  else
311  {
312  yCError(NAVIGATION2DSERVER) << "getNavigationStatus() failed";
313  reply.addVocab(VOCAB_ERR);
314  }
315  }
316  else if (request == VOCAB_NAV_STOP)
317  {
318  bool ret = iNav_ctrl->stopNavigation();
319  if (ret)
320  {
321  reply.addVocab(VOCAB_OK);
322  }
323  else
324  {
325  yCError(NAVIGATION2DSERVER) << "stopNavigation() failed";
326  reply.addVocab(VOCAB_ERR);
327  }
328  }
329  else if (request == VOCAB_NAV_SUSPEND)
330  {
331  double time = -1;
332  if (command.size() > 1)
333  {
334  time = command.get(1).asFloat64();
335  bool ret = iNav_ctrl->suspendNavigation(time);
336  if (ret)
337  {
338  reply.addVocab(VOCAB_OK);
339  }
340  else
341  {
342  yCError(NAVIGATION2DSERVER) << "suspendNavigation() failed";
343  reply.addVocab(VOCAB_ERR);
344  }
345  }
346  else
347  {
348  bool ret = iNav_ctrl->suspendNavigation();
349  if (ret)
350  {
351  reply.addVocab(VOCAB_OK);
352  }
353  else
354  {
355  yCError(NAVIGATION2DSERVER) << "suspendNavigation() failed";
356  reply.addVocab(VOCAB_ERR);
357  }
358  }
359  }
360  else if (request == VOCAB_NAV_RESUME)
361  {
362  bool ret = iNav_ctrl->resumeNavigation();
363  if (ret)
364  {
365  reply.addVocab(VOCAB_OK);
366  }
367  else
368  {
369  yCError(NAVIGATION2DSERVER) << "resumeNavigation failed()";
370  reply.addVocab(VOCAB_ERR);
371  }
372  }
373  else if (request == VOCAB_NAV_GET_NAVIGATION_WAYPOINTS)
374  {
375  Map2DPath locs;
377  if (ret)
378  {
379  reply.addVocab(VOCAB_OK);
380  Bottle& waypoints = reply.addList();
381  for (auto it = locs.begin(); it!=locs.end(); it++)
382  {
383  Bottle& the_waypoint = waypoints.addList();
384  the_waypoint.addString(it->map_id);
385  the_waypoint.addFloat64(it->x);
386  the_waypoint.addFloat64(it->y);
387  the_waypoint.addFloat64(it->theta);
388  }
389  }
390  else
391  {
392  yCError(NAVIGATION2DSERVER) << "getAllNavigationWaypoints() failed";
393  reply.addVocab(VOCAB_ERR);
394  }
395  }
396  else if (request == VOCAB_NAV_GET_CURRENT_WAYPOINT)
397  {
398  Map2DLocation loc;
400  if (ret)
401  {
402  reply.addVocab(VOCAB_OK);
403  reply.addString(loc.map_id);
404  reply.addFloat64(loc.x);
405  reply.addFloat64(loc.y);
406  reply.addFloat64(loc.theta);
407  }
408  else
409  {
410  yCError(NAVIGATION2DSERVER) << "getCurrentNavigationWaypoint() failed";
411  reply.addVocab(VOCAB_ERR);
412  }
413  }
414  else if (request == VOCAB_NAV_GET_NAV_MAP)
415  {
416  MapGrid2D map;
418  {
419  reply.addVocab(VOCAB_OK);
420  yarp::os::Bottle& mapbot = reply.addList();
421  Property::copyPortable(map, mapbot);
422  }
423  else
424  {
425  yCError(NAVIGATION2DSERVER) << "getCurrentNavigationMap() failed";
426  reply.addVocab(VOCAB_ERR);
427  }
428  }
429  else if (request == VOCAB_NAV_GET_ABS_TARGET)
430  {
431  Map2DLocation loc;
432  bool ret;
434  if (ret)
435  {
436  reply.addVocab(VOCAB_OK);
437  reply.addString(loc.map_id);
438  reply.addFloat64(loc.x);
439  reply.addFloat64(loc.y);
440  reply.addFloat64(loc.theta);
441  }
442  else
443  {
444  yCError(NAVIGATION2DSERVER) << "getAbsoluteLocationOfCurrentTarget() failed";
445  reply.addVocab(VOCAB_ERR);
446  }
447  }
448  else if (request == VOCAB_NAV_GET_REL_TARGET)
449  {
450  Map2DLocation loc;
451  bool ret;
453  if (ret)
454  {
455  reply.addVocab(VOCAB_OK);
456  reply.addFloat64(loc.x);
457  reply.addFloat64(loc.y);
458  reply.addFloat64(loc.theta);
459  }
460  else
461  {
462  yCError(NAVIGATION2DSERVER) << "getRelativeLocationOfCurrentTarget() failed";
463  reply.addVocab(VOCAB_ERR);
464  }
465  }
466  else
467  {
468  yCError(NAVIGATION2DSERVER) << "Invalid vocab received";
469  reply.addVocab(VOCAB_ERR);
470  }
471 
472  return true;
473 }
474 
476 {
477  yarp::os::Bottle command;
478  yarp::os::Bottle reply;
479  bool ok = command.read(connection);
480  if (!ok) return false;
481  reply.clear();
482 
483  //^^^^^^^^^^^^^^^^^ STRING SECTION
484  if (command.get(0).isString())
485  {
486  parse_respond_string(command, reply);
487  }
488  //^^^^^^^^^^^^^^^^^ VOCAB SECTION
489  else if (command.get(0).isVocab())
490  {
491  parse_respond_vocab(command, reply);
492  }
493  else
494  {
495  yCError(NAVIGATION2DSERVER) << "Invalid command type";
496  reply.addVocab(VOCAB_ERR);
497  }
498 
499  yarp::os::ConnectionWriter *returnToSender = connection.getWriter();
500  if (returnToSender != nullptr)
501  {
502  reply.write(*returnToSender);
503  }
504 
505  return true;
506 }
507 
509 {
511 
512  double m_stats_time_curr = yarp::os::Time::now();
513  if (m_stats_time_curr - m_stats_time_last > 5.0)
514  {
515  if (!ok)
516  {
517  yCError(NAVIGATION2DSERVER, "Unable to get Navigation Status!\n");
518  }
519  else
520  {
521  yCInfo(NAVIGATION2DSERVER) << "Running, ALL ok. Navigation status:" << getStatusAsString(m_navigation_status);
522  }
524  }
525 }
526 
527 std::string navigation2DServer::getStatusAsString(NavigationStatusEnum status)
528 {
529  if (status == navigation_status_idle) return std::string("navigation_status_idle");
530  else if (status == navigation_status_moving) return std::string("navigation_status_moving");
531  else if (status == navigation_status_waiting_obstacle) return std::string("navigation_status_waiting_obstacle");
532  else if (status == navigation_status_goal_reached) return std::string("navigation_status_goal_reached");
533  else if (status == navigation_status_aborted) return std::string("navigation_status_aborted");
534  else if (status == navigation_status_failing) return std::string("navigation_status_failing");
535  else if (status == navigation_status_paused) return std::string("navigation_status_paused");
536  else if (status == navigation_status_preparing_before_move) return std::string("navigation_status_preparing_before_move");
537  else if (status == navigation_status_thinking) return std::string("navigation_status_thinking");
538  else if (status == navigation_status_error) return std::string("navigation_status_error");
539  return std::string("navigation_status_error");
540 }
LogStream.h
navigation2DServer::detachAll
virtual bool detachAll() override
Detach the object (you must have first called attach).
Definition: navigation2DServer.cpp:81
navigation2DServer::pNav
yarp::dev::PolyDriver pNav
Definition: navigation2DServer.h:58
INavigation2D.h
yarp::os::Bottle
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:73
yarp::os::Value::asVocab
virtual std::int32_t asVocab() const
Get vocabulary identifier as an integer.
Definition: Value.cpp:231
MapGrid2D.h
contains the definition of a map type
navigation2DServer::m_rpcPort
yarp::os::Port m_rpcPort
Definition: navigation2DServer.h:51
yarp::os::Property::put
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:998
yarp::os::Bottle::clear
void clear()
Empties the bottle of any objects it contains.
Definition: Bottle.cpp:124
yarp::dev::Nav2D::navigation_status_thinking
@ navigation_status_thinking
Definition: INavigation2D.h:41
Network.h
navigation2DServer::open
virtual bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
Definition: navigation2DServer.cpp:92
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
yarp::os::Bottle::size
size_type size() const
Gets the number of elements in the bottle.
Definition: Bottle.cpp:254
yarp::dev::Nav2D::INavigation2DTargetActions::applyVelocityCommand
virtual bool applyVelocityCommand(double x_vel, double y_vel, double theta_vel, double timeout=0.1)=0
Apply a velocity command.
VOCAB_NAV_GET_ABS_TARGET
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_ABS_TARGET
Definition: ILocalization2D.h:119
yarp::dev::Map2DLocationData::y
double y
Definition: Map2DLocationData.h:32
VOCAB_NAV_SUSPEND
constexpr yarp::conf::vocab32_t VOCAB_NAV_SUSPEND
Definition: INavigation2D.h:308
Port.h
yarp::os::Searchable::toString
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
yarp::os::Property::fromString
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1046
yarp::dev::PolyDriverList::size
int size() const
Definition: PolyDriverList.cpp:39
yarp::dev::PolyDriver::isValid
bool isValid() const
Check if device is valid.
Definition: PolyDriver.cpp:199
yarp::dev::Nav2D::INavigation2DControlActions::resumeNavigation
virtual bool resumeNavigation()=0
Resume a previously suspended navigation task.
YARP_LOG_COMPONENT
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
yarp::dev::Nav2D::TrajectoryTypeEnum
TrajectoryTypeEnum
Definition: INavigation2D.h:52
navigation2DServer::m_navigation_status
yarp::dev::Nav2D::NavigationStatusEnum m_navigation_status
Definition: navigation2DServer.h:55
VOCAB_NAV_GET_CURRENT_WAYPOINT
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_CURRENT_WAYPOINT
Definition: INavigation2D.h:311
yarp::dev::DeviceDriver::view
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:77
yarp::dev::Nav2D::NavigationStatusEnum
NavigationStatusEnum
Definition: INavigation2D.h:32
yarp::os::Port::open
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: Port.cpp:82
ret
bool ret
Definition: ImplementAxisInfo.cpp:72
yarp::dev::PolyDriverList
Definition: PolyDriverList.h:22
ControlBoardInterfaces.h
define control board standard interfaces
navigation2DServer::m_stats_time_last
double m_stats_time_last
Definition: navigation2DServer.h:63
yarp::os::Bottle::addFloat64
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
Definition: Bottle.cpp:161
yarp::dev::PolyDriver::open
bool open(const std::string &txt)
Construct and configure a device by its common name.
Definition: PolyDriver.cpp:143
yarp::dev::Map2DLocationData::theta
double theta
Definition: Map2DLocationData.h:33
navigation2DServer::read
virtual bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: navigation2DServer.cpp:475
yarp::dev::Nav2D::Map2DPath::begin
iterator begin() noexcept
Returns an iterator to the begin of the Path.
Definition: Map2DPath.cpp:106
VOCAB_NAV_VELOCITY_CMD
constexpr yarp::conf::vocab32_t VOCAB_NAV_VELOCITY_CMD
Definition: ILocalization2D.h:114
yarp::os::Time::now
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:124
yarp::dev::Nav2D::INavigation2DTargetActions::getAbsoluteLocationOfCurrentTarget
virtual bool getAbsoluteLocationOfCurrentTarget(yarp::dev::Nav2D::Map2DLocation &loc)=0
Gets the last navigation target in the world reference frame.
yarp::dev
An interface for the device drivers.
Definition: audioBufferSizeData.cpp:17
navigation2DServer::run
virtual void run() override
Loop function.
Definition: navigation2DServer.cpp:508
yarp::dev::PolyDriverList::push
void push(PolyDriver *p, const char *k)
Definition: PolyDriverList.cpp:44
navigation2DServer::m_rpcPortName
std::string m_rpcPortName
Definition: navigation2DServer.h:52
VOCAB_NAV_GOTOABS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GOTOABS
Definition: ILocalization2D.h:112
yarp::dev::Nav2D::INavigation2DControlActions::stopNavigation
virtual bool stopNavigation()=0
Terminates the current navigation task.
yarp::os::Value::isString
virtual bool isString() const
Checks if value is a string.
Definition: Value.cpp:159
yarp::dev::Nav2D::navigation_status_paused
@ navigation_status_paused
Definition: INavigation2D.h:40
VOCAB_NAV_GET_NAVIGATION_WAYPOINTS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_NAVIGATION_WAYPOINTS
Definition: INavigation2D.h:310
VOCAB_NAV_GET_NAV_MAP
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_NAV_MAP
Definition: INavigation2D.h:312
yarp::dev::Nav2D::INavigation2DTargetActions::gotoTargetByRelativeLocation
virtual bool gotoTargetByRelativeLocation(double x, double y)=0
Ask the robot to reach a position defined in the robot reference frame.
yarp::os::Bottle::get
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:249
VOCAB_NAV_GET_NAVIGATION_STATUS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_NAVIGATION_STATUS
Definition: ILocalization2D.h:128
yarp::os::Bottle::addList
Bottle & addList()
Places an empty nested list in the bottle, at the end of the list.
Definition: Bottle.cpp:185
yarp::os::Bottle::write
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
Definition: Bottle.cpp:233
yarp::dev::Nav2D::MapGrid2D
Definition: MapGrid2D.h:32
yarp::os::ConnectionWriter
An interface for writing to a network connection.
Definition: ConnectionWriter.h:40
yarp::dev::Nav2D::INavigation2DControlActions::getNavigationStatus
virtual bool getNavigationStatus(NavigationStatusEnum &status)=0
Gets the current status of the navigation task.
yarp::dev::Nav2D::INavigation2DControlActions::suspendNavigation
virtual bool suspendNavigation(const double time_s=std::numeric_limits< double >::infinity())=0
Ask to the robot to suspend the current navigation task for a defined amount of time.
yarp::os::Value::asString
virtual std::string asString() const
Get string value.
Definition: Value.cpp:237
VOCAB_NAV_GET_REL_TARGET
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_REL_TARGET
Definition: ILocalization2D.h:120
yarp::dev::PolyDriver
A container for a device driver.
Definition: PolyDriver.h:27
yarp::os::Searchable::check
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
navigation2DServer::m_period
double m_period
Definition: navigation2DServer.h:62
yarp::os::Searchable::find
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
yarp::os::Bottle::addInt32
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
Definition: Bottle.cpp:143
yarp::os::Vocab::encode
NetInt32 encode(const std::string &str)
Convert a string into a vocabulary identifier.
Definition: Vocab.cpp:14
yarp::dev::Nav2D::navigation_status_moving
@ navigation_status_moving
Definition: INavigation2D.h:35
navigation2DServer::initialize_YARP
bool initialize_YARP(yarp::os::Searchable &config)
Definition: navigation2DServer.cpp:151
yarp::dev::Nav2D::navigation_status_failing
@ navigation_status_failing
Definition: INavigation2D.h:39
RFModule.h
yarp::dev::Nav2D::navigation_status_goal_reached
@ navigation_status_goal_reached
Definition: INavigation2D.h:37
yarp::os::ConnectionReader::getWriter
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
yarp::dev::Nav2D::navigation_status_idle
@ navigation_status_idle
Definition: INavigation2D.h:33
yarp::dev::Nav2D::Map2DPath
Definition: Map2DPath.h:27
yarp::dev::Nav2D
Definition: ILocalization2D.h:21
yarp::os::Bottle::addString
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition: Bottle.cpp:173
yarp::os::Port::setReader
void setReader(PortReader &reader) override
Set an external reader for port data.
Definition: Port.cpp:505
yarp::os::PeriodicThread
An abstraction for a periodic thread.
Definition: PeriodicThread.h:25
yarp::os::Bottle::addVocab
void addVocab(int x)
Places a vocabulary item in the bottle, at the end of the list.
Definition: Bottle.cpp:167
LogComponent.h
VOCAB_ERR
constexpr yarp::conf::vocab32_t VOCAB_ERR
Definition: GenericVocabs.h:20
yarp::dev::Nav2D::navigation_status_aborted
@ navigation_status_aborted
Definition: INavigation2D.h:38
yarp::dev::Nav2D::Map2DLocation
Definition: Map2DLocation.h:30
yarp::dev::Nav2D::INavigation2DTargetActions::gotoTargetByAbsoluteLocation
virtual bool gotoTargetByAbsoluteLocation(yarp::dev::Nav2D::Map2DLocation loc)=0
Ask the robot to reach a position defined in the world reference frame.
yarp::os::ConnectionReader
An interface for reading from a network connection.
Definition: ConnectionReader.h:40
navigation2DServer::iNav_ctrl
yarp::dev::Nav2D::INavigation2DControlActions * iNav_ctrl
Definition: navigation2DServer.h:59
yCError
#define yCError(component,...)
Definition: LogComponent.h:157
yarp::dev::Nav2D::navigation_status_waiting_obstacle
@ navigation_status_waiting_obstacle
Definition: INavigation2D.h:36
VOCAB_NAV_RESUME
constexpr yarp::conf::vocab32_t VOCAB_NAV_RESUME
Definition: INavigation2D.h:309
yarp::os::Value::asInt32
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:207
yCInfo
#define yCInfo(component,...)
Definition: LogComponent.h:135
yarp::dev::Nav2D::NavigationMapTypeEnum
NavigationMapTypeEnum
Definition: INavigation2D.h:46
yarp::dev::Nav2D::INavigation2DControlActions::getAllNavigationWaypoints
virtual bool getAllNavigationWaypoints(yarp::dev::Nav2D::TrajectoryTypeEnum trajectory_type, yarp::dev::Nav2D::Map2DPath &waypoints)=0
Returns the list of waypoints generated by the navigation algorithm.
yarp::os
An interface to the operating system, including Port based communication.
Definition: AbstractCarrier.h:17
yCDebug
#define yCDebug(component,...)
Definition: LogComponent.h:112
VOCAB_NAV_STOP
constexpr yarp::conf::vocab32_t VOCAB_NAV_STOP
Definition: INavigation2D.h:307
DEFAULT_THREAD_PERIOD
#define DEFAULT_THREAD_PERIOD
Definition: AnalogWrapper.h:45
yarp::dev::Nav2D::INavigation2DTargetActions::getRelativeLocationOfCurrentTarget
virtual bool getRelativeLocationOfCurrentTarget(double &x, double &y, double &theta)=0
Gets the last navigation target in the robot reference frame.
yarp::dev::Nav2D::Map2DPath::end
iterator end() noexcept
Returns an iterator to the end of the Path.
Definition: Map2DPath.cpp:112
navigation2DServer::iNav_target
yarp::dev::Nav2D::INavigation2DTargetActions * iNav_target
Definition: navigation2DServer.h:60
navigation2DServer::m_streamingPortName
std::string m_streamingPortName
Definition: navigation2DServer.h:53
navigation2DServer::navigation2DServer
navigation2DServer()
Default module constructor.
Definition: navigation2DServer.cpp:47
VOCAB_NAV_RECOMPUTE_PATH
constexpr yarp::conf::vocab32_t VOCAB_NAV_RECOMPUTE_PATH
Definition: ILocalization2D.h:115
yarp::os::Bottle::read
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Definition: Bottle.cpp:243
yarp::dev::Nav2D::INavigation2DControlActions::getCurrentNavigationWaypoint
virtual bool getCurrentNavigationWaypoint(yarp::dev::Nav2D::Map2DLocation &curr_waypoint)=0
Returns the current waypoint pursued by the navigation algorithm.
yarp::dev::Nav2D::navigation_status_error
@ navigation_status_error
Definition: INavigation2D.h:42
Time.h
yarp::dev::Map2DLocationData::x
double x
Definition: Map2DLocationData.h:31
VOCAB_NAV_GOTOREL
constexpr yarp::conf::vocab32_t VOCAB_NAV_GOTOREL
Definition: ILocalization2D.h:113
yarp::dev::Nav2D::INavigation2DControlActions::recomputeCurrentNavigationPath
virtual bool recomputeCurrentNavigationPath()=0
Forces the navigation system to recompute the path from the current robot position to the current goa...
yarp::dev::Nav2D::INavigation2DControlActions::getCurrentNavigationMap
virtual bool getCurrentNavigationMap(yarp::dev::Nav2D::NavigationMapTypeEnum map_type, yarp::dev::Nav2D::MapGrid2D &map)=0
Returns the current navigation map processed by the navigation algorithm.
yCTrace
#define yCTrace(component,...)
Definition: LogComponent.h:88
navigation2DServer::close
virtual bool close() override
Close the DeviceDriver.
Definition: navigation2DServer.cpp:162
yarp::dev::Map2DLocationData::map_id
std::string map_id
Definition: Map2DLocationData.h:30
yarp::os::Value::asFloat64
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:225
VOCAB_OK
constexpr yarp::conf::vocab32_t VOCAB_OK
Definition: GenericVocabs.h:18
yarp::dev::Nav2D::navigation_status_preparing_before_move
@ navigation_status_preparing_before_move
Definition: INavigation2D.h:34
VOCAB_INAVIGATION
constexpr yarp::conf::vocab32_t VOCAB_INAVIGATION
Definition: ILocalization2D.h:110
navigation2DServer::attachAll
virtual bool attachAll(const yarp::dev::PolyDriverList &l) override
Attach to a list of objects.
Definition: navigation2DServer.cpp:54
yarp::os::Value::isVocab
virtual bool isVocab() const
Checks if value is a vocabulary identifier.
Definition: Value.cpp:177
yarp::os::Property
A class for storing options and configuration information.
Definition: Property.h:37
navigation2DServer.h