YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
Localization2D_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#define _USE_MATH_DEFINES
7
9
10#include <yarp/os/Bottle.h>
12#include <yarp/os/LogStream.h>
13#include <yarp/os/Network.h>
14#include <yarp/os/Port.h>
15#include <yarp/os/RFModule.h>
16#include <yarp/os/Time.h>
17
18#include <yarp/sig/Vector.h>
19
22#include <yarp/dev/IMap2D.h>
23#include <yarp/dev/PolyDriver.h>
24
25#include <yarp/math/Math.h>
26
27#include <cmath>
28
31using namespace yarp::os;
32using namespace yarp::dev;
33using namespace yarp::dev::Nav2D;
34
35#define DEFAULT_THREAD_PERIOD 0.01
36
37namespace {
38YARP_LOG_COMPONENT(LOCALIZATION2D_NWS_ROS, "yarp.device.localization2D_nws_ros")
39}
40
41//------------------------------------------------------------------------------------------------------------------------------
42
48
50{
51 if (driver->isValid())
52 {
53 driver->view(iLoc);
54 }
55
56 if (nullptr == iLoc)
57 {
58 yCError(LOCALIZATION2D_NWS_ROS, "Unable to view ILocalization2D interface. Attach failed?");
59 return false;
60 }
61
62 //initialize m_current_position and m_current_status, if available
63 bool ret = true;
65 Map2DLocation loc;
66 ret &= iLoc->getLocalizationStatus(status);
68 if (ret)
69 {
70 m_current_status = status;
72 }
73 else
74 {
75 yCWarning(LOCALIZATION2D_NWS_ROS) << "Localization data not yet available during server initialization";
76 }
77
79 return PeriodicThread::start();
80}
81
83{
85 {
87 }
88 iLoc = nullptr;
89 return true;
90}
91
93{
94 Property params;
95 params.fromString(config.toString().c_str());
96 yCDebug(LOCALIZATION2D_NWS_ROS) << "Configuration: \n" << config.toString().c_str();
97
98 if (!config.check("period"))
99 {
100 yCInfo(LOCALIZATION2D_NWS_ROS) << "Missing 'period' parameter. Using default value: " << DEFAULT_THREAD_PERIOD;
102 }
103 else
104 {
105 m_period = config.find("period").asFloat64();
106 yCInfo(LOCALIZATION2D_NWS_ROS) << "Period requested: " << m_period;
107 }
108
109 if (!config.check("publish_odometry"))
110 {
111 m_enable_publish_odometry_topic = config.find("publish_odometry").asBool();
113 }
114 if (!config.check("publish_tf"))
115 {
116 m_enable_publish_odometry_tf = config.find("publish_tf").asBool();
118 }
119
120 if (!config.check("yarp_base_name"))
121 {
122 yCError(LOCALIZATION2D_NWS_ROS) << "Missing yarp_base_name parameter";
123 return false;
124 }
125 m_local_name = config.find("yarp_base_name").asString();
126 if (m_local_name.c_str()[0] != '/') {
127 yCError(LOCALIZATION2D_NWS_ROS) << "Missing '/' in yarp_base_name parameter";
128 return false;
129 }
130
131 m_rpcPortName = m_local_name + "/rpc";
132
133 yCInfo(LOCALIZATION2D_NWS_ROS) << "Waiting for device to attach";
134
136
137 if (!initialize_YARP(config))
138 {
139 yCError(LOCALIZATION2D_NWS_ROS) << "Error initializing YARP ports";
140 return false;
141 }
142
143 if (!initialize_ROS(config))
144 {
145 yCError(LOCALIZATION2D_NWS_ROS) << "Error initializing ROS system";
146 return false;
147 }
148
149 return true;
150}
151
153{
154 if (params.check("parent_frame_id"))
155 {
156 m_parent_frame_id = params.find("parent_frame_id").asString();
157 }
158
159 if (params.check("child_frame_id"))
160 {
161 m_child_frame_id = params.find("child_frame_id").asString();
162 }
163
164 if (params.check("topic_name"))
165 {
166 m_odom_topic_name = params.find("topic_name").asString();
167 }
168
169 if (params.check("node_name"))
170 {
171 m_node_name = params.find("node_name").asString();
172 }
174
175 if (m_node == nullptr)
176 {
177 bool b= false;
179 if (m_node == nullptr)
180 {
181 yCError(LOCALIZATION2D_NWS_ROS) << "Opening " << m_node_name << " Node, check your yarp-ROS network configuration";
182 return false;
183 }
184
186 if (!b)
187 {
188 yCError(LOCALIZATION2D_NWS_ROS) << "Unable to publish data on" << m_odom_topic_name << "topic";
189 return false;
190 }
191 b = m_tf_publisher.topic("/tf");
192 if (!b)
193 {
194 yCError(LOCALIZATION2D_NWS_ROS) << "Unable to publish data on /tf topic";
195 return false;
196 }
197 yCInfo(LOCALIZATION2D_NWS_ROS) << "ROS initialized";
198 }
199 return true;
200}
201
203{
204 if (!m_rpcPort.open(m_rpcPortName.c_str()))
205 {
206 yCError(LOCALIZATION2D_NWS_ROS, "Failed to open port %s", m_rpcPortName.c_str());
207 return false;
208 }
209 m_rpcPort.setReader(*this);
210
211 return true;
212}
213
215{
218 {
220 }
221
222 detach();
223
226
227 if (m_node)
228 {
231 delete m_node;
232 m_node = nullptr;
233 }
234
235 yCDebug(LOCALIZATION2D_NWS_ROS) << "Execution terminated";
236 return true;
237}
238
240{
241 yarp::os::Bottle command;
242 yarp::os::Bottle reply;
243 bool ok = command.read(connection);
244 if (!ok) {
245 return false;
246 }
247
248 reply.clear();
249
250 if (command.get(0).isString() && command.get(0).asString() == "help")
251 {
252 reply.addVocab32("many");
253 reply.addString("No commands currently available:");
254 }
255 else
256 {
257 yCError(LOCALIZATION2D_NWS_ROS) << "Invalid command. Try `help`";
258 reply.addVocab32(VOCAB_ERR);
259 }
260
262 if (returnToSender != nullptr)
263 {
264 reply.write(*returnToSender);
265 }
266
267 return true;
268}
269
271{
274 {
275 yCInfo(LOCALIZATION2D_NWS_ROS) << "Running";
277 }
278
280 if (ret == false)
281 {
282 yCError(LOCALIZATION2D_NWS_ROS) << "getLocalizationStatus() failed";
283 }
284
285 if (m_current_status == LocalizationStatusEnum::localization_status_localized_ok)
286 {
288 if (ret2 == false)
289 {
290 yCError(LOCALIZATION2D_NWS_ROS) << "getCurrentPosition() failed";
291 }
292 else
293 {
295 }
297 if (ret3 == false)
298 {
299 //yCError(LOCALIZATION2D_NWS_ROS) << "getEstimatedOdometry() failed";
300 }
301 else
302 {
304 }
305 }
306 else
307 {
308 yCWarning(LOCALIZATION2D_NWS_ROS, "The system is not properly localized!");
309 }
310
312 publish_odometry_on_ROS_topic();
313 }
315 publish_odometry_on_TF_topic();
316 }
317}
318
319void Localization2D_nws_ros::publish_odometry_on_TF_topic()
320{
321 yarp::rosmsg::tf2_msgs::TFMessage& rosData = m_tf_publisher.prepare();
322 yarp::rosmsg::geometry_msgs::TransformStamped transform;
323 transform.child_frame_id = m_child_frame_id;
324 transform.header.frame_id = m_parent_frame_id;
325 transform.header.seq = m_odom_stamp.getCount();
326 transform.header.stamp = m_odom_stamp.getTime();
327 double halfYaw = m_current_odometry.odom_theta / 180.0 * M_PI * 0.5;
328 double cosYaw = cos(halfYaw);
329 double sinYaw = sin(halfYaw);
330 transform.transform.rotation.x = 0;
331 transform.transform.rotation.y = 0;
332 transform.transform.rotation.z = sinYaw;
333 transform.transform.rotation.w = cosYaw;
334 transform.transform.translation.x = m_current_odometry.odom_x;
335 transform.transform.translation.y = m_current_odometry.odom_y;
336 transform.transform.translation.z = 0;
337 if (rosData.transforms.size() == 0)
338 {
339 rosData.transforms.push_back(transform);
340 }
341 else
342 {
343 rosData.transforms[0] = transform;
344 }
345
347}
348
349void Localization2D_nws_ros::publish_odometry_on_ROS_topic()
350{
352 {
353 yarp::rosmsg::nav_msgs::Odometry& odom = m_odometry_publisher.prepare();
354 odom.clear();
355 odom.header.frame_id = m_fixed_frame;
356 odom.header.seq = m_odom_stamp.getCount();
357 odom.header.stamp = m_odom_stamp.getTime();
358 odom.child_frame_id = m_robot_frame;
359
360 odom.pose.pose.position.x = m_current_odometry.odom_x;
361 odom.pose.pose.position.y = m_current_odometry.odom_y;
362 odom.pose.pose.position.z = 0;
364 vecrpy[0] = 0;
365 vecrpy[1] = 0;
369 odom.pose.pose.orientation.x = q.x();
370 odom.pose.pose.orientation.y = q.y();
371 odom.pose.pose.orientation.z = q.z();
372 odom.pose.pose.orientation.w = q.w();
373 //odom.pose.covariance = 0;
374
375 odom.twist.twist.linear.x = m_current_odometry.base_vel_x;
376 odom.twist.twist.linear.y = m_current_odometry.base_vel_y;
377 odom.twist.twist.linear.z = 0;
378 odom.twist.twist.angular.x = 0;
379 odom.twist.twist.angular.y = 0;
380 odom.twist.twist.angular.z = m_current_odometry.base_vel_theta;
381 //odom.twist.covariance = 0;
382
384 }
385}
define control board standard interfaces
#define M_PI
#define DEFAULT_THREAD_PERIOD
constexpr yarp::conf::vocab32_t VOCAB_ERR
bool ret
#define DEFAULT_THREAD_PERIOD
contains the definition of a Vector type
bool close() override
Close the DeviceDriver.
bool initialize_YARP(yarp::os::Searchable &config)
yarp::dev::OdometryData m_current_odometry
yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry > m_odometry_publisher
yarp::dev::Nav2D::ILocalization2D * iLoc
yarp::dev::Nav2D::Map2DLocation m_current_position
bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
yarp::dev::Nav2D::LocalizationStatusEnum m_current_status
yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage > m_tf_publisher
bool detach() override
Detach the object (you must have first called attach).
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
void run() override
Loop function.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
bool initialize_ROS(yarp::os::Searchable &config)
bool view(T *&x)
Get an interface to the device driver.
virtual yarp::dev::ReturnValue getLocalizationStatus(LocalizationStatusEnum &status)=0
Gets the current status of the localization task.
virtual yarp::dev::ReturnValue getCurrentPosition(yarp::dev::Nav2D::Map2DLocation &loc)=0
Gets the current position of the robot w.r.t world reference frame.
virtual yarp::dev::ReturnValue getEstimatedOdometry(yarp::dev::OdometryData &odom)=0
Gets the estimated odometry the robot, including its velocity expressed in the world and in the local...
double base_vel_x
velocity of the robot [m/s] expressed in the robot reference frame
double base_vel_theta
angular velocity of the robot [deg/s] expressed in the robot reference frame
double base_vel_y
velocity of the robot [m/s] expressed in the robot reference frame
double odom_x
position of the robot [m], expressed in the world reference frame
double odom_y
position of the robot [m], expressed in the world reference frame
double odom_theta
orientation the robot [deg], expressed 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.
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
An abstraction for a periodic thread.
bool setPeriod(double period)
Set the (new) period of the thread.
bool isRunning() const
Returns true when the thread is started, false otherwise.
bool start()
Call this to start the thread.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
int getOutputCount() override
Determine how many output connections this port has.
Definition Port.cpp:567
void setReader(PortReader &reader) override
Set an external reader for port data.
Definition Port.cpp:511
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition Port.cpp:383
void close() override
Stop port activity.
Definition Port.cpp:363
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition Port.cpp:79
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 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.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition Stamp.cpp:124
double getTime() const
Get the time stamp.
Definition Stamp.cpp:34
int getCount() const
Get the sequence number.
Definition Stamp.cpp:29
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 yCDebug(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
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.