YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
Map2D_nws_ros2.cpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#ifndef _USE_MATH_DEFINES
7#define _USE_MATH_DEFINES
8#endif
9
10#include "Map2D_nws_ros2.h"
11
12#include <chrono>
13#include <vector>
14#include <cmath>
15#include <yarp/dev/IMap2D.h>
18#include <yarp/math/Math.h>
19#include <yarp/os/Log.h>
21#include <yarp/os/LogStream.h>
22#include <mutex>
23#include <cstdlib>
24#include <fstream>
25#include <Ros2Utils.h>
26#include <rclcpp/qos.hpp>
27#include <rclcpp/version.h>
28
29using namespace yarp::sig;
30using namespace yarp::dev;
31using namespace yarp::dev::Nav2D;
32using namespace yarp::os;
33using namespace std;
34using namespace std::placeholders;
35
36namespace {
37YARP_LOG_COMPONENT(MAP2D_NWS_ROS2, "yarp.device.map2D_nws_ros2")
38}
39
40
43
45{
46 if (driver->isValid())
47 {
48 driver->view(m_iMap2D);
50 m_iMap2D->get_map_names(maps);
51 m_currentMapName = maps[0];
52 }
53
54 if (nullptr == m_iMap2D)
55 {
56 yCError(MAP2D_NWS_ROS2, "Subdevice passed to attach method is invalid");
57 return false;
58 }
59
60 return true;
61}
62
64{
65 m_iMap2D = nullptr;
66 return true;
67}
68
70{
71 parseParams(config);
72
73 if(m_name[0] == '/'){
74 yCError(MAP2D_NWS_ROS2) << "Nws name parameter cannot begin with an initial /";
75 return false;
76 }
77
78 m_rpcPortName = "/"+m_name+"/rpc";
79
80 //open rpc port
81 if (!m_rpcPort.open(m_rpcPortName))
82 {
83 yCError(MAP2D_NWS_ROS2, "Failed to open port %s", m_rpcPortName.c_str());
84 return false;
85 }
86 m_rpcPort.setReader(*this);
87
88 //ROS2 configuration
89 if(m_node_name[0] == '/'){
90 yCError(MAP2D_NWS_ROS2) << "node_name cannot begin with an initial /";
91 return false;
92 }
96 qos_rmw.depth=10;
97 rmw_time_t time;
98 time.sec=10000;
99 time.nsec = 0;
100 qos_rmw.deadline= time;
101 qos_rmw.lifespan=time;
102 qos_rmw.liveliness_lease_duration=time;
106 qos_rmw.avoid_ros_namespace_conventions = true;
107 m_ros2Service_getMap = m_node->create_service<nav_msgs::srv::GetMap>(m_getmap,
108 std::bind(&Map2D_nws_ros2::getMapCallback,this,_1,_2,_3),
109#if RCLCPP_VERSION_GTE(17,0,0)
110 rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_rmw))
111#else
112 qos_rmw
113#endif
114 );
115 m_ros2Service_getMapByName = m_node->create_service<map2d_nws_ros2_msgs::srv::GetMapByName>(m_getmapbyname,
116 std::bind(&Map2D_nws_ros2::getMapByNameCallback,this,_1,_2,_3));
117 m_ros2Service_rosCmdParser = m_node->create_service<test_msgs::srv::BasicTypes>(m_roscmdparser,
118 std::bind(&Map2D_nws_ros2::rosCmdParserCallback,this,_1,_2,_3));
119
120 yCInfo(MAP2D_NWS_ROS2) << "Waiting for device to attach";
121 start();
122
123 return true;
124}
125
126
128{
129
130// if(!m_spinned) //This is just a temporary solution.
131// {
132// rclcpp::spin(m_node);
133// m_spinned = true;
134// }
135}
136
138{
139 yCTrace(MAP2D_NWS_ROS2, "Close");
140 m_rpcPort.close();
141 rclcpp::shutdown();
142 return true;
143}
144
146{
147 yCWarning(MAP2D_NWS_ROS2) << "not yet implemented";
148
149 std::lock_guard<std::mutex> lock(m_mutex);
152 bool ok = in.read(connection);
153 if (!ok) return false;
154
155 //parse string command
156 if(in.get(0).isString())
157 {
158 // parse_string_command(in, out);
159 }
160 // parse vocab command
161 else if(in.get(0).isVocab32())
162 {
163 // parse_vocab_command(in, out);
164 }
165
167 if (returnToSender != nullptr)
168 {
169 out.write(*returnToSender);
170 }
171 else
172 {
173 yCError(MAP2D_NWS_ROS2) << "Invalid return to sender";
174 }
175 return true;
176}
177
179{
180 if (!m_ros2Publisher_markers)
181 {
182 m_ros2Publisher_markers = m_node->create_publisher<visualization_msgs::msg::MarkerArray>(m_markers_pub, 10);
183 }
184 builtin_interfaces::msg::Duration dur;
185 dur.sec = 0xFFFFFFFF;
187 uint64_t time;
189 rclcpp::Time ret;
190 time = (uint64_t)(yarpTimeStamp * 1000000000UL);
191 sec_part = (time / 1000000000UL);
192 if (sec_part > std::numeric_limits<unsigned int>::max())
193 {
194 yCWarning(MAP2D_NWS_ROS2) << "Timestamp exceeded the 64 bit representation, resetting it to 0";
195 sec_part = 0;
196 }
197 visualization_msgs::msg::Marker marker;
198 builtin_interfaces::msg::Time tt;
199 yarp::sig::Vector rpy(3);
201 visualization_msgs::msg::MarkerArray markers;
202
203 std::vector<std::string> locations;
204 int count = 1;
205 m_iMap2D->getLocationsList(locations);
206 for (auto it : locations)
207 {
209 m_iMap2D->getLocation(it, loc);
210
211 if(loc.map_id != m_currentMapName && m_currentMapName != "none")
212 {
213 continue;
214 }
215
216 rpy[0] = 0; //x
217 rpy[1] = 0; //y
218 rpy[2] = loc.theta / 180 * M_PI; //z
221
222 marker.header.frame_id = "map";
224 marker.header.stamp = tt;
225 marker.ns = m_markers_pub+"_ns";
226 marker.id = count;
227 marker.type = visualization_msgs::msg::Marker::ARROW;//yarp::rosmsg::visualization_msgs::Marker::ARROW;
228 marker.action = visualization_msgs::msg::Marker::ADD;//yarp::rosmsg::visualization_msgs::Marker::ADD;
229 marker.pose.position.x = loc.x;
230 marker.pose.position.y = loc.y;
231 marker.pose.position.z = 0;
232 marker.pose.orientation.x = q.x();
233 marker.pose.orientation.y = q.y();
234 marker.pose.orientation.z = q.z();
235 marker.pose.orientation.w = q.w();
236 marker.scale.x = 1;
237 marker.scale.y = 0.1;
238 marker.scale.z = 0.1;
239 marker.color.a = 1.0;
240 marker.color.r = 0.0;
241 marker.color.g = 1.0;
242 marker.color.b = 0.0;
243 marker.lifetime = dur;
244 marker.text = it;
245 markers.markers.push_back(marker);
246 count++;
247 }
248
249 m_ros2Publisher_markers->publish(markers);
250 return true;
251}
252
253
254void Map2D_nws_ros2::getMapCallback(const std::shared_ptr<rmw_request_id_t> request_header,
255 const std::shared_ptr<nav_msgs::srv::GetMap::Request> request,
256 std::shared_ptr<nav_msgs::srv::GetMap::Response> response)
257{
258 yCWarning(MAP2D_NWS_ROS2) << "Not yet implemented";
259 nav_msgs::msg::OccupancyGrid mapToGo;
260 mapToGo.header.frame_id = "map";
261
262 response->map = mapToGo;
263}
264
265void Map2D_nws_ros2::rosCmdParserCallback(const std::shared_ptr<rmw_request_id_t> request_header,
266 const std::shared_ptr<test_msgs::srv::BasicTypes::Request> request,
267 std::shared_ptr<test_msgs::srv::BasicTypes::Response> response)
268{
269 if(request->string_value == "updatemarkerviz")
270 {
271 if(updateVizMarkers()) response->set__string_value("done");
272 else response->set__string_value("error");
273 }
274 else
275 {
276 response->set__string_value("unknown_command");
277 }
278}
279
280//void Map2D_nws_ros2::prepareMapMsg(MapGrid2D inputMap, nav_msgs::msg::OccupancyGrid &outputMsg)
281void Map2D_nws_ros2::getMapByNameCallback(const std::shared_ptr<rmw_request_id_t> request_header,
282 const std::shared_ptr<map2d_nws_ros2_msgs::srv::GetMapByName::Request> request,
283 std::shared_ptr<map2d_nws_ros2_msgs::srv::GetMapByName::Response> response)
284{
285 if (!m_ros2Publisher_map)
286 {
287 m_ros2Publisher_map = m_node->create_publisher<nav_msgs::msg::OccupancyGrid>(m_getmapbyname+"/pub", 10);
288 }
289 nav_msgs::msg::OccupancyGrid mapToGo;
290 nav_msgs::msg::MapMetaData metaToGo;
291 mapToGo.header.frame_id = "map";
293 if(!m_iMap2D->get_map(request->name,theMap))
294 {
295 mapToGo.header.frame_id = "invalid_frame";
296 response->map = mapToGo;
297 return;
298 }
299 mapToGo.info.map_load_time = m_node->get_clock()->now();
300 mapToGo.header.stamp = m_node->get_clock()->now();
301 mapToGo.info.height = theMap.height();
302 mapToGo.info.width = theMap.width();
303
304 double DEG2RAD = M_PI/180.0;
305 double tmp=0;
306 theMap.getResolution(tmp);
307 mapToGo.info.resolution=tmp;
308 double x, y, t;
309 theMap.getOrigin(x,y,t);
310 mapToGo.info.origin.position.x=x;
311 mapToGo.info.origin.position.y=y;
314 v[0]=0; v[1]=0; v[2]=1; v[3]=t*DEG2RAD;
315 q.fromAxisAngle(v);
316 mapToGo.info.origin.orientation.x = q.x();
317 mapToGo.info.origin.orientation.y = q.y();
318 mapToGo.info.origin.orientation.z = q.z();
319 mapToGo.info.origin.orientation.w = q.w();
320 mapToGo.data.resize(theMap.width()*theMap.height());
321 int index=0;
323 for (cell.y=theMap.height(); cell.y-- > 0;)
324 {
325 for (cell.x=0; cell.x<theMap.width(); cell.x++)
326 {
327 theMap.getOccupancyData(cell,tmp);
328 mapToGo.data[index++]=(int)tmp;
329 }
330 }
331
332 response->map = mapToGo;
333 m_currentMapName = request->name;
334
335 metaToGo.map_load_time = mapToGo.info.map_load_time;
336 metaToGo.height = theMap.height();
337 metaToGo.width = theMap.width();
338 metaToGo.origin = mapToGo.info.origin;
339 metaToGo.resolution = mapToGo.info.resolution;
340
341 if (m_ros2Publisher_map)
342 {
343 m_ros2Publisher_map->publish(mapToGo);
344 }
345}
#define M_PI
bool ret
#define DEG2RAD
bool parseParams(const yarp::os::Searchable &config) override
Parse the DeviceDriver parameters.
void getMapCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav_msgs::srv::GetMap::Request > request, std::shared_ptr< nav_msgs::srv::GetMap::Response > response)
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
void getMapByNameCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< map2d_nws_ros2_msgs::srv::GetMapByName::Request > request, std::shared_ptr< map2d_nws_ros2_msgs::srv::GetMapByName::Response > response)
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
bool close() override
Close the DeviceDriver.
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
void rosCmdParserCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< test_msgs::srv::BasicTypes::Request > request, std::shared_ptr< test_msgs::srv::BasicTypes::Response > response)
void run() override
Main body of the new thread.
bool detach() override
Detach the object (you must have first called attach).
static rclcpp::Node::SharedPtr createNode(std::string name)
Definition Ros2Utils.cpp:9
bool view(T *&x)
Get an interface to the device driver.
std::string map_id
name of the map
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 get_map_names(std::vector< std::string > &map_names)=0
Gets a list containing the names of all registered maps.
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 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.
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.
void close() override
Stop port activity.
A simple collection of objects that can be described and transmitted in a portable way.
Definition Bottle.h:65
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Definition Bottle.cpp:246
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition Bottle.cpp:252
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
Definition Bottle.cpp:236
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.
A base class for nested structures that can be searched.
Definition Searchable.h:31
bool start()
Start the new thread running.
Definition Thread.cpp:93
virtual bool isString() const
Checks if value is a string.
Definition Value.cpp:156
virtual bool isVocab32() const
Checks if value is a 32bit vocabulary identifier.
Definition Value.cpp:174
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,...)
STL namespace.
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
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