21#include <yarp/rosmsg/TickDuration.h>
22#include <yarp/rosmsg/TickTime.h>
40#define M_PI 3.14159265358979323846
43#define RAD2DEG 180/M_PI
44#define DEG2RAD M_PI/180
52 m_enable_publish_map =
false;
53 m_enable_subscribe_map =
false;
63 bool ok = command.
read(connection);
73 reply.
addString(
"No commands currently available:");
95 if (!config.
check(
"name"))
97 m_rpcPortName =
"/map2D_nws_ros/rpc";
101 m_rpcPortName = config.
find(
"name").asString();
107 if (!m_rpcPort.
open(m_rpcPortName))
115 if (config.
check(
"ROS"))
120 if (
ROS_config.find(
"enable_publisher").asInt32() == 1 ||
ROS_config.find(
"enable_publisher").asString() ==
"true")
122 m_enable_publish_map =
true;
126 if (
ROS_config.find(
"enable_subscriber").asInt32() == 1 ||
ROS_config.find(
"enable_subscriber").asString() ==
"true")
128 m_enable_subscribe_map =
true;
132 if (m_enable_publish_map)
134 if (m_node ==
nullptr)
152 if (m_enable_subscribe_map)
180bool Map2D_nws_ros::publishMapToRos(std::string map_name)
190 yarp::rosmsg::nav_msgs::OccupancyGrid&
ogrid = m_publisherPort_map.
prepare();
196 ogrid.header.frame_id =
"map";
197 ogrid.info.map_load_time.sec = 0;
198 ogrid.info.map_load_time.nsec = 0;
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;
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();
222 m_publisherPort_map.
write();
230bool Map2D_nws_ros::subscribeMapFromRos(std::string map_name)
234 yarp::rosmsg::nav_msgs::OccupancyGrid*
map_ros =
nullptr;
235 yarp::rosmsg::nav_msgs::MapMetaData*
metamap_ros =
nullptr;
242 std::string map_name =
"ros_map";
248 map_ros->info.origin.orientation.y,
249 map_ros->info.origin.orientation.z,
250 map_ros->info.origin.orientation.w);
255 for (
size_t y = 0; y <
map_ros->info.height; y++)
257 for (
size_t x = 0; x <
map_ros->info.width; x++)
263 if (
occ >= 0 &&
occ <= 70) {
265 }
else if (
occ >= 71 &&
occ <= 100) {
288 if (m_enable_publish_map)
292 m_publisherPort_map.
close();
293 m_publisherPort_metamap.
close();
295 if (m_enable_subscribe_map)
299 m_subscriberPort_map.
close();
300 m_subscriberPort_metamap.
close();
305bool Map2D_nws_ros::updateVizMarkers(std::string map_name)
309 m_publisherPort_markers.
topic(
"/locationServerMarkers");
311 yarp::rosmsg::TickDuration
dur;
dur.sec = 0xFFFFFFFF;
316 yarp::rosmsg::TickTime
ret;
320 if (
sec_part > std::numeric_limits<unsigned int>::max())
326 yarp::rosmsg::visualization_msgs::Marker
marker;
327 yarp::rosmsg::TickTime
tt;
331 yarp::rosmsg::visualization_msgs::MarkerArray&
markers = m_publisherPort_markers.
prepare();
334 std::vector<std::string> locations;
337 for (
auto it : locations)
343 rpy[2] = loc.
theta / 180 * 3.14159265359;
347 marker.header.frame_id =
"map";
351 marker.ns =
"my_namespace";
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();
375 m_publisherPort_markers.
write();
390 driver->
view(m_iMap2D);
393 if (
nullptr == m_iMap2D)
constexpr yarp::conf::vocab32_t VOCAB_ERR
#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 ¶ms) 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.
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.
A simple collection of objects that can be described and transmitted in a portable way.
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
void clear()
Empties the bottle of any objects it contains.
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
void addString(const char *str)
Places a string in the bottle, at the end of the list.
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.
bool isOpen() const
Check if the port has been opened.
A class for storing options and configuration information.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
void close() override
Stop port activity.
bool topic(const std::string &name)
Set topic to publish to.
Port & asPort() override
Get the concrete Port being used for communication.
void interrupt() override
Interrupt any current reads or writes attached to the port.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
A base class for nested structures that can be searched.
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.
void close() override
Stop port activity.
void setStrict(bool strict=true)
bool topic(const std::string &name)
Set topic to subscribe to.
void interrupt() override
Interrupt any current reads or writes attached to the port.
virtual bool isString() const
Checks if value is a string.
virtual std::string asString() const
Get string value.
#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...
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....
double now()
Return the current time in seconds, relative to an arbitrary starting point.
An interface to the operating system, including Port based communication.
std::uint32_t NetUint32
Definition of the NetUint32 type.