|  | YARP Yet Another Robot Platform |  | 
 
 
 
Go to the documentation of this file.
   19 #define _USE_MATH_DEFINES 
   44 #define RAD2DEG 180.0/M_PI 
   56     if (device2attach.
size() != 1)
 
   58         yCError(NAVIGATION2DSERVER, 
"Cannot attach more than one device");
 
   73         yCError(NAVIGATION2DSERVER, 
"Subdevice passed to attach method is invalid");
 
   78     return PeriodicThread::start();
 
   83     if (PeriodicThread::isRunning())
 
   85         PeriodicThread::stop();
 
   96     yCDebug(NAVIGATION2DSERVER) << 
"Configuration: \n" << config.
toString().c_str();
 
   98     if (!config.
check(
"period"))
 
  100         yCInfo(NAVIGATION2DSERVER) << 
"Missing 'period' parameter. Using default value: 0.010";
 
  108     string local_name = 
"/navigationServer";
 
  109     if (!config.
check(
"name"))
 
  111         yCInfo(NAVIGATION2DSERVER) << 
"Missing 'name' parameter. Using default value: /navigationServer";
 
  120     if (config.
check(
"subdevice"))
 
  129             yCError(NAVIGATION2DSERVER) << 
"Failed to open subdevice.. check params";
 
  136             yCError(NAVIGATION2DSERVER) << 
"Failed to open subdevice.. check params";
 
  144         yCError(NAVIGATION2DSERVER) << 
"Error initializing YARP ports";
 
  164     yCTrace(NAVIGATION2DSERVER, 
"Close");
 
  165     if (PeriodicThread::isRunning())
 
  167         PeriodicThread::stop();
 
  178         yCError(NAVIGATION2DSERVER) << 
"General error in navigation2DServer::parse_respond_string()";
 
  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.");
 
  190         reply.
addString(
"Unknown command. Type 'help'.");
 
  199         yCError(NAVIGATION2DSERVER) << 
"General error in navigation2DServer::parse_respond_vocab()";
 
  206         yCError(NAVIGATION2DSERVER) << 
"Invalid vocab received";
 
  226             yCError(NAVIGATION2DSERVER) << 
"gotoTargetByAbsoluteLocation() failed";
 
  239             yCError(NAVIGATION2DSERVER) << 
"recomputeCurrentNavigationPath() failed";
 
  246         if (command.
size() == 5)
 
  258                 yCError(NAVIGATION2DSERVER) << 
"gotoTargetByRelativeLocation() failed";
 
  262         else if (command.
size() == 4)
 
  273                 yCError(NAVIGATION2DSERVER) << 
"gotoTargetByRelativeLocation() failed";
 
  279             yCError(NAVIGATION2DSERVER) << 
"Invalid number of params";
 
  297             yCError(NAVIGATION2DSERVER) << 
"applyVelocityCommand() failed";
 
  312             yCError(NAVIGATION2DSERVER) << 
"getNavigationStatus() failed";
 
  325             yCError(NAVIGATION2DSERVER) << 
"stopNavigation() failed";
 
  332         if (command.
size() > 1)
 
  342                 yCError(NAVIGATION2DSERVER) << 
"suspendNavigation() failed";
 
  355                 yCError(NAVIGATION2DSERVER) << 
"suspendNavigation() failed";
 
  369             yCError(NAVIGATION2DSERVER) << 
"resumeNavigation failed()";
 
  381             for (
auto it = locs.
begin(); it!=locs.
end(); it++)
 
  392             yCError(NAVIGATION2DSERVER) << 
"getAllNavigationWaypoints() failed";
 
  410             yCError(NAVIGATION2DSERVER) << 
"getCurrentNavigationWaypoint() failed";
 
  421             Property::copyPortable(map, mapbot);
 
  425             yCError(NAVIGATION2DSERVER) << 
"getCurrentNavigationMap() failed";
 
  444             yCError(NAVIGATION2DSERVER) << 
"getAbsoluteLocationOfCurrentTarget() failed";
 
  462             yCError(NAVIGATION2DSERVER) << 
"getRelativeLocationOfCurrentTarget() failed";
 
  468         yCError(NAVIGATION2DSERVER) << 
"Invalid vocab received";
 
  479     bool ok = command.
read(connection);
 
  480     if (!ok) 
return false;
 
  486         parse_respond_string(command, reply);
 
  491         parse_respond_vocab(command, reply);
 
  495         yCError(NAVIGATION2DSERVER) << 
"Invalid command type";
 
  500     if (returnToSender != 
nullptr)
 
  502         reply.
write(*returnToSender);
 
  517             yCError(NAVIGATION2DSERVER, 
"Unable to get Navigation Status!\n");
 
  539     return std::string(
"navigation_status_error");
 
  
 
virtual bool detachAll() override
Detach the object (you must have first called attach).
yarp::dev::PolyDriver pNav
A simple collection of objects that can be described and transmitted in a portable way.
virtual std::int32_t asVocab() const
Get vocabulary identifier as an integer.
contains the definition of a map type
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
void clear()
Empties the bottle of any objects it contains.
@ navigation_status_thinking
virtual bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
A base class for nested structures that can be searched.
size_type size() const
Gets the number of elements in the bottle.
virtual bool applyVelocityCommand(double x_vel, double y_vel, double theta_vel, double timeout=0.1)=0
Apply a velocity command.
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_ABS_TARGET
constexpr yarp::conf::vocab32_t VOCAB_NAV_SUSPEND
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
bool isValid() const
Check if device is valid.
virtual bool resumeNavigation()=0
Resume a previously suspended navigation task.
#define YARP_LOG_COMPONENT(name,...)
yarp::dev::Nav2D::NavigationStatusEnum m_navigation_status
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_CURRENT_WAYPOINT
bool view(T *&x)
Get an interface to the device driver.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
define control board standard interfaces
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
bool open(const std::string &txt)
Construct and configure a device by its common name.
virtual bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
iterator begin() noexcept
Returns an iterator to the begin of the Path.
constexpr yarp::conf::vocab32_t VOCAB_NAV_VELOCITY_CMD
double now()
Return the current time in seconds, relative to an arbitrary starting point.
virtual bool getAbsoluteLocationOfCurrentTarget(yarp::dev::Nav2D::Map2DLocation &loc)=0
Gets the last navigation target in the world reference frame.
An interface for the device drivers.
virtual void run() override
Loop function.
void push(PolyDriver *p, const char *k)
std::string m_rpcPortName
constexpr yarp::conf::vocab32_t VOCAB_NAV_GOTOABS
virtual bool stopNavigation()=0
Terminates the current navigation task.
virtual bool isString() const
Checks if value is a string.
@ navigation_status_paused
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_NAVIGATION_WAYPOINTS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_NAV_MAP
virtual bool gotoTargetByRelativeLocation(double x, double y)=0
Ask the robot to reach a position defined in the robot reference frame.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_NAVIGATION_STATUS
Bottle & addList()
Places an empty nested list in the bottle, at the end of the list.
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
An interface for writing to a network connection.
virtual bool getNavigationStatus(NavigationStatusEnum &status)=0
Gets the current status of the navigation task.
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.
virtual std::string asString() const
Get string value.
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_REL_TARGET
A container for a device driver.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
NetInt32 encode(const std::string &str)
Convert a string into a vocabulary identifier.
@ navigation_status_moving
bool initialize_YARP(yarp::os::Searchable &config)
@ navigation_status_failing
@ navigation_status_goal_reached
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
void addString(const char *str)
Places a string in the bottle, at the end of the list.
void setReader(PortReader &reader) override
Set an external reader for port data.
An abstraction for a periodic thread.
void addVocab(int x)
Places a vocabulary item in the bottle, at the end of the list.
constexpr yarp::conf::vocab32_t VOCAB_ERR
@ navigation_status_aborted
virtual bool gotoTargetByAbsoluteLocation(yarp::dev::Nav2D::Map2DLocation loc)=0
Ask the robot to reach a position defined in the world reference frame.
An interface for reading from a network connection.
yarp::dev::Nav2D::INavigation2DControlActions * iNav_ctrl
#define yCError(component,...)
@ navigation_status_waiting_obstacle
constexpr yarp::conf::vocab32_t VOCAB_NAV_RESUME
virtual std::int32_t asInt32() const
Get 32-bit integer value.
#define yCInfo(component,...)
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.
An interface to the operating system, including Port based communication.
#define yCDebug(component,...)
constexpr yarp::conf::vocab32_t VOCAB_NAV_STOP
#define DEFAULT_THREAD_PERIOD
virtual bool getRelativeLocationOfCurrentTarget(double &x, double &y, double &theta)=0
Gets the last navigation target in the robot reference frame.
iterator end() noexcept
Returns an iterator to the end of the Path.
yarp::dev::Nav2D::INavigation2DTargetActions * iNav_target
std::string m_streamingPortName
navigation2DServer()
Default module constructor.
constexpr yarp::conf::vocab32_t VOCAB_NAV_RECOMPUTE_PATH
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
virtual bool getCurrentNavigationWaypoint(yarp::dev::Nav2D::Map2DLocation &curr_waypoint)=0
Returns the current waypoint pursued by the navigation algorithm.
@ navigation_status_error
constexpr yarp::conf::vocab32_t VOCAB_NAV_GOTOREL
virtual bool recomputeCurrentNavigationPath()=0
Forces the navigation system to recompute the path from the current robot position to the current goa...
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.
#define yCTrace(component,...)
virtual bool close() override
Close the DeviceDriver.
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
constexpr yarp::conf::vocab32_t VOCAB_OK
@ navigation_status_preparing_before_move
constexpr yarp::conf::vocab32_t VOCAB_INAVIGATION
virtual bool attachAll(const yarp::dev::PolyDriverList &l) override
Attach to a list of objects.
virtual bool isVocab() const
Checks if value is a vocabulary identifier.
A class for storing options and configuration information.