YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
Map2D_nws_ros.cpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: LGPL-2.1-or-later
4 */
5
6#include "Map2D_nws_ros.h"
7
8#include <yarp/os/Log.h>
10#include <yarp/os/LogStream.h>
11#include <yarp/os/Node.h>
12#include <yarp/os/Publisher.h>
13#include <yarp/os/Subscriber.h>
14
16#include <yarp/dev/IMap2D.h>
18
19#include <yarp/math/Math.h>
20
21#include <yarp/rosmsg/TickDuration.h>
22#include <yarp/rosmsg/TickTime.h>
23
24#include <cstdlib>
25#include <fstream>
26#include <limits>
27#include <mutex>
28#include <sstream>
29
30using namespace yarp::sig;
31using namespace yarp::dev;
32using namespace yarp::dev::Nav2D;
33using namespace yarp::os;
34
35namespace {
36YARP_LOG_COMPONENT(MAP2D_NWS_ROS, "yarp.device.map2D_nws_ros")
37}
38
39#ifndef M_PI
40#define M_PI 3.14159265358979323846
41#endif
42
43#define RAD2DEG 180/M_PI
44#define DEG2RAD M_PI/180
45
51{
52 m_enable_publish_map = false;
53 m_enable_subscribe_map = false;
54 m_node = nullptr;
55}
56
58
59bool Map2D_nws_ros::read(yarp::os::ConnectionReader& connection)
60{
61 yarp::os::Bottle command;
62 yarp::os::Bottle reply;
63 bool ok = command.read(connection);
64 if (!ok) {
65 return false;
66 }
67
68 reply.clear();
69
70 if (command.get(0).isString() && command.get(0).asString() == "help")
71 {
72 reply.addVocab32("many");
73 reply.addString("No commands currently available:");
74 }
75 else
76 {
77 yCError(MAP2D_NWS_ROS) << "Invalid command. Try `help`";
78 reply.addVocab32(VOCAB_ERR);
79 }
80
82 if (returnToSender != nullptr)
83 {
84 reply.write(*returnToSender);
85 }
86
87 return true;
88}
89
91{
92 Property params;
93 params.fromString(config.toString());
94
95 if (!config.check("name"))
96 {
97 m_rpcPortName = "/map2D_nws_ros/rpc";
98 }
99 else
100 {
101 m_rpcPortName = config.find("name").asString();
102 }
103
104 yCInfo(MAP2D_NWS_ROS) << "Waiting for device to attach";
105
106 //open rpc port
107 if (!m_rpcPort.open(m_rpcPortName))
108 {
109 yCError(MAP2D_NWS_ROS, "Failed to open port %s", m_rpcPortName.c_str());
110 return false;
111 }
112 m_rpcPort.setReader(*this);
113
114 //ROS configuration
115 if (config.check("ROS"))
116 {
117 yCInfo(MAP2D_NWS_ROS, "Configuring ROS params");
118 Bottle ROS_config = config.findGroup("ROS");
119
120 if (ROS_config.find("enable_publisher").asInt32() == 1 || ROS_config.find("enable_publisher").asString() == "true")
121 {
122 m_enable_publish_map = true;
123 yCInfo(MAP2D_NWS_ROS) << "Enabled ROS publisher";
124 }
125
126 if (ROS_config.find("enable_subscriber").asInt32() == 1 || ROS_config.find("enable_subscriber").asString() == "true")
127 {
128 m_enable_subscribe_map = true;
129 yCInfo(MAP2D_NWS_ROS) << "Enabled ROS subscriber";
130 }
131
132 if (m_enable_publish_map)
133 {
134 if (m_node == nullptr)
135 {
136 m_node = new yarp::os::Node(ROSNODENAME);
137 }
138 if (!m_publisherPort_map.topic(ROSTOPICNAME_MAP))
139 {
140 yCError(MAP2D_NWS_ROS) << "Unable to publish to" << ROSTOPICNAME_MAP << "topic, check your YARP-ROS network configuration";
141 return false;
142 }
143 if (!m_publisherPort_metamap.topic(ROSTOPICNAME_MAPMETADATA))
144 {
145 yCError(MAP2D_NWS_ROS) << "Unable to publish to " << ROSTOPICNAME_MAPMETADATA << " topic, check your YARP-ROS network configuration";
146 return false;
147 }
148 //should I publish the map now? with which name ?
149 //publishMapToRos();
150 }
151
152 if (m_enable_subscribe_map)
153 {
154 if (!m_subscriberPort_map.topic(ROSTOPICNAME_MAP))
155 {
156 yCError(MAP2D_NWS_ROS) << "Unable to subscribe to " << ROSTOPICNAME_MAP << " topic, check your YARP-ROS network configuration";
157 return false;
158 }
159 if (!m_subscriberPort_metamap.topic(ROSTOPICNAME_MAPMETADATA))
160 {
161 yCError(MAP2D_NWS_ROS) << "Unable to subscribe to " << ROSTOPICNAME_MAPMETADATA << " topic, check your YARP-ROS network configuration";
162 return false;
163 }
164 m_subscriberPort_map.setStrict();
165 m_subscriberPort_metamap.setStrict();
166
167 //should I subscribe the map now ? with which name ?
168 //subscribeMapFromRos();
169 }
170 }
171 else
172 {
173 //no ROS options
174 yCWarning(MAP2D_NWS_ROS) << "ROS Group not configured";
175 }
176
177 return true;
178}
179
180bool Map2D_nws_ros::publishMapToRos(std::string map_name)
181{
183 if (!m_iMap2D->get_map(map_name, current_map))
184 {
185 yCError(MAP2D_NWS_ROS) << "publishMapToRos() " << map_name << " does not exists";
186 return false;
187 }
188
189 double tmp = 0;
190 yarp::rosmsg::nav_msgs::OccupancyGrid& ogrid = m_publisherPort_map.prepare();
191 ogrid.clear();
192 ogrid.info.height = current_map.height();
193 ogrid.info.width = current_map.width();
194 current_map.getResolution(tmp);
195 ogrid.info.resolution = tmp;
196 ogrid.header.frame_id = "map";
197 ogrid.info.map_load_time.sec = 0;
198 ogrid.info.map_load_time.nsec = 0;
199 double x, y, t;
200 current_map.getOrigin(x, y, t);
201 ogrid.info.origin.position.x = x;
202 ogrid.info.origin.position.y = y;
205 v[0] = 0; v[1] = 0; v[2] = 1; v[3] = t * DEG2RAD;
206 q.fromAxisAngle(v);
207 ogrid.info.origin.orientation.x = q.x();
208 ogrid.info.origin.orientation.y = q.y();
209 ogrid.info.origin.orientation.z = q.z();
210 ogrid.info.origin.orientation.w = q.w();
211 ogrid.data.resize(current_map.width() * current_map.height());
212 int index = 0;
214 for (cell.y = current_map.height(); cell.y-- > 0;) {
215 for (cell.x = 0; cell.x < current_map.width(); cell.x++)
216 {
217 current_map.getOccupancyData(cell, tmp);
218 ogrid.data[index++] = (int)tmp;
219 }
220 }
221
222 m_publisherPort_map.write();
223
224 //what about the m_publisherPort_metamap ?
225 //I don't know...
226
227 return true;
228}
229
230bool Map2D_nws_ros::subscribeMapFromRos(std::string map_name)
231{
232 //In this block receives data from a ROS topic and stores data on attached device
233 //yarp::os::Time::delay(5);
234 yarp::rosmsg::nav_msgs::OccupancyGrid* map_ros = nullptr;
235 yarp::rosmsg::nav_msgs::MapMetaData* metamap_ros = nullptr;
236
237 map_ros = m_subscriberPort_map.read(true);
238 metamap_ros = m_subscriberPort_metamap.read(true);
239 if (map_ros != nullptr && metamap_ros != nullptr)
240 {
241 yCInfo(MAP2D_NWS_ROS) << "Received map for ROS";
242 std::string map_name = "ros_map";
243 MapGrid2D map;
244 map.setSize_in_cells(map_ros->info.width,map_ros->info.height);
245 map.setResolution(map_ros->info.resolution);
246 map.setMapName(map_name);
247 yarp::math::Quaternion quat(map_ros->info.origin.orientation.x,
248 map_ros->info.origin.orientation.y,
249 map_ros->info.origin.orientation.z,
250 map_ros->info.origin.orientation.w);
251 yarp::sig::Matrix mat = quat.toRotationMatrix4x4();
253 double orig_angle = vec[2];
254 map.setOrigin(map_ros->info.origin.position.x,map_ros->info.origin.position.y,orig_angle);
255 for (size_t y = 0; y < map_ros->info.height; y++)
256 {
257 for (size_t x = 0; x < map_ros->info.width; x++)
258 {
259 XYCell cell(x,map_ros->info.height - 1 - y);
260 double occ = map_ros->data[x + y * map_ros->info.width];
262
263 if (occ >= 0 && occ <= 70) {
265 } else if (occ >= 71 && occ <= 100) {
267 } else {
269 }
270 }
271 }
272 if (m_iMap2D->store_map(map))
273 {
274 yCInfo(MAP2D_NWS_ROS) << "Added map " << map.getMapName() << " to storage";
275 return true;
276 }
277
278 yCInfo(MAP2D_NWS_ROS) << "Unable to add map " << map.getMapName() << " to storage";
279 return false;
280 }
281
282 return false;
283}
284
286{
287 yCTrace(MAP2D_NWS_ROS, "Close");
288 if (m_enable_publish_map)
289 {
290 m_publisherPort_map.interrupt();
291 m_publisherPort_metamap.interrupt();
292 m_publisherPort_map.close();
293 m_publisherPort_metamap.close();
294 }
295 if (m_enable_subscribe_map)
296 {
297 m_subscriberPort_map.interrupt();
298 m_subscriberPort_metamap.interrupt();
299 m_subscriberPort_map.close();
300 m_subscriberPort_metamap.close();
301 }
302 return true;
303}
304
305bool Map2D_nws_ros::updateVizMarkers(std::string map_name)
306{
307 if (m_publisherPort_markers.asPort().isOpen()==false)
308 {
309 m_publisherPort_markers.topic("/locationServerMarkers");
310 }
311 yarp::rosmsg::TickDuration dur; dur.sec = 0xFFFFFFFF;
313 uint64_t time;
316 yarp::rosmsg::TickTime ret;
317 time = (uint64_t)(yarpTimeStamp * 1000000000UL);
318 nsec_part = (time % 1000000000UL);
319 sec_part = (time / 1000000000UL);
320 if (sec_part > std::numeric_limits<unsigned int>::max())
321 {
322 yCWarning(MAP2D_NWS_ROS) << "Timestamp exceeded the 64 bit representation, resetting it to 0";
323 sec_part = 0;
324 }
325
326 yarp::rosmsg::visualization_msgs::Marker marker;
327 yarp::rosmsg::TickTime tt;
328 yarp::sig::Vector rpy(3);
330
331 yarp::rosmsg::visualization_msgs::MarkerArray& markers = m_publisherPort_markers.prepare();
332 markers.markers.clear();
333
334 std::vector<std::string> locations;
335 int count = 1;
336 m_iMap2D->getLocationsList(locations);
337 for (auto it : locations)
338 {
340 m_iMap2D->getLocation(it, loc);
341 rpy[0] = 0; //x
342 rpy[1] = 0; //y
343 rpy[2] = loc.theta / 180 * 3.14159265359; //z
346
347 marker.header.frame_id = "map";
350 marker.header.stamp = tt;
351 marker.ns = "my_namespace";
352 marker.id = count;
353 marker.type = yarp::rosmsg::visualization_msgs::Marker::ARROW;
354 marker.action = yarp::rosmsg::visualization_msgs::Marker::ADD;
355 marker.pose.position.x = loc.x;
356 marker.pose.position.y = loc.y;
357 marker.pose.position.z = 0;
358 marker.pose.orientation.x = q.x();
359 marker.pose.orientation.y = q.y();
360 marker.pose.orientation.z = q.z();
361 marker.pose.orientation.w = q.w();
362 marker.scale.x = 1;
363 marker.scale.y = 0.1;
364 marker.scale.z = 0.1;
365 marker.color.a = 1.0;
366 marker.color.r = 0.0;
367 marker.color.g = 1.0;
368 marker.color.b = 0.0;
369 marker.lifetime = dur;
370 marker.text = it;
371 markers.markers.push_back(marker);
372 count++;
373 }
374
375 m_publisherPort_markers.write();
376 return true;
377}
378
379
381{
382 m_iMap2D = nullptr;
383 return true;
384}
385
387{
388 if (driver->isValid())
389 {
390 driver->view(m_iMap2D);
391 }
392
393 if (nullptr == m_iMap2D)
394 {
395 yCError(MAP2D_NWS_ROS, "Unable to view IMap2D interface. Attach failed");
396 return false;
397 }
398
399 return true;
400}
constexpr yarp::conf::vocab32_t VOCAB_ERR
bool ret
#define DEG2RAD
#define ROSTOPICNAME_MAP
#define ROSNODENAME
#define ROSTOPICNAME_MAPMETADATA
bool close() override
Close the DeviceDriver.
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
bool detach() override
Detach the object (you must have first called attach).
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
Map2D_nws_ros()
Map2D_nws_ros.
bool view(T *&x)
Get an interface to the device driver.
double theta
orientation [deg] in the map reference frame
double y
y position of the location [m], expressed in the map reference frame
double x
x position of the location [m], expressed in the map reference frame
virtual yarp::dev::ReturnValue getLocationsList(std::vector< std::string > &locations)=0
Get a list of the names of all stored locations.
virtual yarp::dev::ReturnValue store_map(const yarp::dev::Nav2D::MapGrid2D &map)=0
Stores a map into the map server.
virtual yarp::dev::ReturnValue get_map(std::string map_name, yarp::dev::Nav2D::MapGrid2D &map)=0
Gets a map from the map server.
virtual yarp::dev::ReturnValue getLocation(std::string location_name, yarp::dev::Nav2D::Map2DLocation &loc)=0
Retrieves a location specified by the user in the world reference frame.
bool setResolution(double resolution)
Sets the resolution of the map, i.e.
bool setOrigin(double x, double y, double theta)
Sets the origin of the map reference frame (according to ROS convention)
std::string getMapName() const
Retrieves the map name.
bool setSize_in_cells(size_t x, size_t y)
Sets the size of the map in cells.
bool setMapName(std::string map_name)
Sets the map name.
bool setMapFlag(XYCell cell, map_flags flag)
Set the flag of a specific cell of the map.
bool setOccupancyData(XYCell cell, double occupancy)
Set the occupancy data of a specific cell of the map.
A container for a device driver.
Definition PolyDriver.h:23
bool isValid() const
Check if device is valid.
void fromRotationMatrix(const yarp::sig::Matrix &R)
Converts a rotation matrix to a quaternion.
void fromAxisAngle(const yarp::sig::Vector &v)
Computes the quaternion from an axis-angle representation.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
void setReader(PortReader &reader) override
Set an external reader for port data.
A simple collection of objects that can be described and transmitted in a portable way.
Definition Bottle.h:64
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
Definition Bottle.cpp:164
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Definition Bottle.cpp:240
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition Bottle.cpp:246
void clear()
Empties the bottle of any objects it contains.
Definition Bottle.cpp:121
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
Definition Bottle.cpp:230
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition Bottle.cpp:170
A mini-server for performing network communication in the background.
An interface for reading from a network connection.
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
An interface for writing to a network connection.
The Node class.
Definition Node.h:23
bool isOpen() const
Check if the port has been opened.
Definition Port.cpp:677
A class for storing options and configuration information.
Definition Property.h:33
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
void close() override
Stop port activity.
Definition Publisher.h:84
bool topic(const std::string &name)
Set topic to publish to.
Definition Publisher.h:63
Port & asPort() override
Get the concrete Port being used for communication.
Definition Publisher.h:169
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition Publisher.h:90
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition Publisher.h:148
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
Definition Publisher.h:123
A base class for nested structures that can be searched.
Definition Searchable.h:31
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
T * read(bool shouldWait=true)
Read a message from the port.
Definition Subscriber.h:113
void close() override
Stop port activity.
Definition Subscriber.h:83
void setStrict(bool strict=true)
Definition Subscriber.h:150
bool topic(const std::string &name)
Set topic to subscribe to.
Definition Subscriber.h:62
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition Subscriber.h:89
virtual bool isString() const
Checks if value is a string.
Definition Value.cpp:156
virtual std::string asString() const
Get string value.
Definition Value.cpp:234
A class for a Matrix.
Definition Matrix.h:39
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
For streams capable of holding different kinds of content, check what they actually have.
yarp::sig::Matrix rpy2dcm(const yarp::sig::Vector &rpy)
Converts roll-pitch-yaw angles in the corresponding dcm (direction cosine matrix) rotation matrix (de...
Definition math.cpp:847
yarp::sig::Vector dcm2rpy(const yarp::sig::Matrix &R)
Converts a dcm (direction cosine matrix) rotation matrix to roll-pitch-yaw angles (defined in Math....
Definition math.cpp:808
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition Time.cpp:121
An interface to the operating system, including Port based communication.
std::uint32_t NetUint32
Definition of the NetUint32 type.
Definition NetUint32.h:29