YARP
Yet Another Robot Platform
Navigation2DClient.h
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 #ifndef YARP_DEV_NAVIGATION2DCLIENT_H
20 #define YARP_DEV_NAVIGATION2DCLIENT_H
21 
22 #include <yarp/os/Network.h>
25 #include <yarp/sig/Vector.h>
26 #include <yarp/os/Time.h>
27 #include <yarp/dev/PolyDriver.h>
28 #include <yarp/dev/INavigation2D.h>
29 
30 #include <mutex>
31 #include <string>
32 
33 #define DEFAULT_THREAD_PERIOD 20 //ms
34 
35 
55 {
56 protected:
57  std::mutex m_mutex;
62  std::string m_local_name;
66  int m_period;
67 
68 private:
69  std::string m_current_goal_name;
70  bool reset_current_goal_name();
71  bool set_current_goal_name(const std::string& name);
72  bool get_current_goal_name(std::string& name);
73 
74 private: //math stuff
75  double normalize_angle(double angle);
76  bool locations_are_similar(yarp::dev::Nav2D::Map2DLocation loc1,
78  double lin_tol,
79  double ang_tol);
80 
81 
82 public:
83 
84  /* DeviceDriver methods */
85  bool open(yarp::os::Searchable& config) override;
86  bool close() override;
87 
88  /* RPC responder */
89  bool parse_respond_string(const yarp::os::Bottle& command, yarp::os::Bottle& reply);
90  virtual bool read(yarp::os::ConnectionReader& connection) override;
91 
92  /* The following methods belong to INavigation2D interface */
93  virtual bool checkInsideArea(yarp::dev::Nav2D::Map2DArea area) override;
94  virtual bool checkInsideArea(std::string area_name) override;
95  virtual bool checkNearToLocation(yarp::dev::Nav2D::Map2DLocation loc, double linear_tolerance, double angular_tolerance = std::numeric_limits<double>::infinity()) override;
96  virtual bool checkNearToLocation(std::string location_name, double linear_tolerance, double angular_tolerance = std::numeric_limits<double>::infinity()) override;
97 
99  bool gotoTargetByLocationName(std::string location_name) override;
100  bool gotoTargetByRelativeLocation(double x, double y, double theta) override;
101  bool gotoTargetByRelativeLocation(double x, double y) override;
102  bool applyVelocityCommand(double x_vel, double y_vel, double theta_vel, double timeout = 0.1) override;
103  bool recomputeCurrentNavigationPath() override;
104 
106  bool getNameOfCurrentTarget(std::string& location_name) override;
107  bool getRelativeLocationOfCurrentTarget(double& x, double& y, double& theta) override;
108 
110  bool getEstimatedOdometry(yarp::dev::OdometryData& odom) override;
111  bool setInitialPose(const yarp::dev::Nav2D::Map2DLocation& loc) override;
113  bool getEstimatedPoses(std::vector<yarp::dev::Nav2D::Map2DLocation>& poses) override;
114  bool setInitialPose(const yarp::dev::Nav2D::Map2DLocation& loc, const yarp::sig::Matrix& cov) override;
116  bool startLocalizationService() override;
117  bool stopLocalizationService() override;
118 
119  bool storeCurrentPosition(std::string location_name) override;
120  bool storeLocation(std::string location_name, yarp::dev::Nav2D::Map2DLocation loc) override;
121  bool getLocation(std::string location_name, yarp::dev::Nav2D::Map2DLocation& loc) override;
122  bool getArea(std::string area_name, yarp::dev::Nav2D::Map2DArea& area) override;
123  bool deleteLocation(std::string location_name) override;
124  bool getLocationsList(std::vector<std::string>& locations) override;
125 
127  bool clearAllLocations() override;
128  bool stopNavigation() override;
129  bool suspendNavigation(const double time_s) override;
130  bool resumeNavigation() override;
134 };
135 
136 #endif // YARP_DEV_NAVIGATION2DCLIENT_H
define control board standard interfaces
contains the definition of a Vector type
bool getLocation(std::string location_name, yarp::dev::Nav2D::Map2DLocation &loc) override
Retrieves a location previously stored by the user.
bool storeCurrentPosition(std::string location_name) override
Store the current location of the robot.
bool getCurrentPosition(yarp::dev::Nav2D::Map2DLocation &loc) override
Gets the current position of the robot w.r.t world reference frame.
bool gotoTargetByRelativeLocation(double x, double y, double theta) override
Ask the robot to reach a position defined in the robot reference frame.
yarp::os::Port m_rpc_port_navigation_server
bool getNavigationStatus(yarp::dev::Nav2D::NavigationStatusEnum &status) override
Gets the current status of the navigation task.
bool parse_respond_string(const yarp::os::Bottle &command, yarp::os::Bottle &reply)
bool getEstimatedOdometry(yarp::dev::OdometryData &odom) override
Gets the estimated odometry the robot, including its velocity expressed in the world and in the local...
bool getLocalizationStatus(yarp::dev::Nav2D::LocalizationStatusEnum &status) override
Gets the current status of the localization task.
bool getEstimatedPoses(std::vector< yarp::dev::Nav2D::Map2DLocation > &poses) override
Gets a set of pose estimates computed by the localization algorithm.
bool storeLocation(std::string location_name, yarp::dev::Nav2D::Map2DLocation loc) override
Store a location specified by the user in the world reference frame.
bool getAllNavigationWaypoints(yarp::dev::Nav2D::TrajectoryTypeEnum trajectory_type, yarp::dev::Nav2D::Map2DPath &waypoints) override
Returns the list of waypoints generated by the navigation algorithm.
bool getAbsoluteLocationOfCurrentTarget(yarp::dev::Nav2D::Map2DLocation &loc) override
Gets the last navigation target in the world reference frame.
virtual bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
virtual bool checkInsideArea(yarp::dev::Nav2D::Map2DArea area) override
Check if the robot is currently inside the specified area.
bool applyVelocityCommand(double x_vel, double y_vel, double theta_vel, double timeout=0.1) override
Apply a velocity command.
bool getNameOfCurrentTarget(std::string &location_name) override
Gets the name of the current target, if available (set by gotoTargetByLocationName)
bool deleteLocation(std::string location_name) override
Delete a location.
yarp::os::Port m_rpc_port_map_locations_server
bool getRelativeLocationOfCurrentTarget(double &x, double &y, double &theta) override
Gets the last navigation target in the robot reference frame.
virtual bool checkNearToLocation(yarp::dev::Nav2D::Map2DLocation loc, double linear_tolerance, double angular_tolerance=std::numeric_limits< double >::infinity()) override
Check if the robot is currently near to the specified area.
bool recomputeCurrentNavigationPath() override
Forces the navigation system to recompute the path from the current robot position to the current goa...
bool getArea(std::string area_name, yarp::dev::Nav2D::Map2DArea &area) override
Retrieves an area previously stored by the user.
bool stopNavigation() override
Terminates the current navigation task.
bool suspendNavigation(const double time_s) override
Ask to the robot to suspend the current navigation task for a defined amount of time.
yarp::os::Port m_rpc_port_user_commands
bool stopLocalizationService() override
Stops the localization service.
bool setInitialPose(const yarp::dev::Nav2D::Map2DLocation &loc) override
Sets the initial pose for the localization algorithm which estimates the current position of the robo...
bool clearAllLocations() override
Delete all stored locations.
bool gotoTargetByAbsoluteLocation(yarp::dev::Nav2D::Map2DLocation loc) override
Ask the robot to reach a position defined in the world reference frame.
bool close() override
Close the DeviceDriver.
std::string m_localization_server_name
bool gotoTargetByLocationName(std::string location_name) override
Ask the robot to reach a previously stored location/area.
bool startLocalizationService() override
Starts the localization service.
bool getCurrentNavigationMap(yarp::dev::Nav2D::NavigationMapTypeEnum map_type, yarp::dev::Nav2D::MapGrid2D &map) override
Returns the current navigation map processed by the navigation algorithm.
bool getCurrentNavigationWaypoint(yarp::dev::Nav2D::Map2DLocation &curr_waypoint) override
Returns the current waypoint pursued by the navigation algorithm.
bool getLocationsList(std::vector< std::string > &locations) override
Get a list of all stored locations.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
std::string m_navigation_server_name
bool resumeNavigation() override
Resume a previously suspended navigation task.
yarp::os::Port m_rpc_port_localization_server
std::string m_map_locations_server_name
Interface implemented by all device drivers.
Definition: DeviceDriver.h:38
An interface to control the navigation of a mobile robot in a 2D environment.
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:73
An interface for reading from a network connection.
Interface implemented by all objects that can read themselves from the network, such as Bottle object...
Definition: PortReader.h:28
A mini-server for network communication.
Definition: Port.h:50
A base class for nested structures that can be searched.
Definition: Searchable.h:69
A class for a Matrix.
Definition: Matrix.h:46