YARP
Yet Another Robot Platform
Localization2DServer.cpp
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 #include <yarp/os/Network.h>
20 #include <yarp/os/RFModule.h>
21 #include <yarp/os/Time.h>
22 #include <yarp/os/Port.h>
23 #include <yarp/os/LogComponent.h>
24 #include <yarp/os/LogStream.h>
25 #include <yarp/dev/PolyDriver.h>
26 #include <yarp/os/Bottle.h>
27 #include <yarp/sig/Vector.h>
28 #include <yarp/dev/IMap2D.h>
31 #include <yarp/math/Math.h>
32 #include "Localization2DServer.h"
33 
34 #include <cmath>
35 
38 using namespace yarp::os;
39 using namespace yarp::dev;
40 using namespace yarp::dev::Nav2D;
41 using namespace std;
42 
43 #define DEFAULT_THREAD_PERIOD 0.01
44 
45 #ifndef M_PI
46 #define M_PI 3.14159265358979323846
47 #endif
48 
49 namespace {
50 YARP_LOG_COMPONENT(LOCALIZATION2DSERVER, "yarp.device.localization2DServer")
51 }
52 
53 //------------------------------------------------------------------------------------------------------------------------------
54 
56 {
57  m_ros_node = nullptr;
61  iLoc = nullptr;
65 }
66 
68 {
69  if (device2attach.size() != 1)
70  {
71  yCError(LOCALIZATION2DSERVER, "Cannot attach more than one device");
72  return false;
73  }
74 
75  yarp::dev::PolyDriver * Idevice2attach = device2attach[0]->poly;
76 
77  if (Idevice2attach->isValid())
78  {
79  Idevice2attach->view(iLoc);
80  }
81 
82  if (nullptr == iLoc)
83  {
84  yCError(LOCALIZATION2DSERVER, "Subdevice passed to attach method is invalid");
85  return false;
86  }
87 
88  //initialize m_current_position and m_current_status, if available
89  bool ret = true;
91  Map2DLocation loc;
92  ret &= iLoc->getLocalizationStatus(status);
93  ret &= iLoc->getCurrentPosition(loc);
94  if (ret)
95  {
96  m_current_status = status;
97  m_current_position = loc;
98  }
99  else
100  {
101  yCWarning(LOCALIZATION2DSERVER) << "Localization data not yet available during server initialization";
102  }
103 
104  PeriodicThread::setPeriod(m_period);
105  return PeriodicThread::start();
106 }
107 
109 {
110  if (PeriodicThread::isRunning())
111  {
112  PeriodicThread::stop();
113  }
114  iLoc = nullptr;
115  return true;
116 }
117 
119 {
120  Property params;
121  params.fromString(config.toString().c_str());
122  yCDebug(LOCALIZATION2DSERVER) << "Configuration: \n" << config.toString().c_str();
123 
124  if (config.check("GENERAL") == false)
125  {
126  yCWarning(LOCALIZATION2DSERVER) << "Missing GENERAL group, assuming default options";
127  }
128 
129  Bottle& general_group = config.findGroup("GENERAL");
130  if (!general_group.check("period"))
131  {
132  yCInfo(LOCALIZATION2DSERVER) << "Missing 'period' parameter. Using default value: " << DEFAULT_THREAD_PERIOD;
134  }
135  else
136  {
137  m_period = general_group.find("period").asFloat64();
138  yCInfo(LOCALIZATION2DSERVER) << "Period requested: " << m_period;
139  }
140 
141  if (!general_group.check("retrieve_position_periodically"))
142  {
143  yCInfo(LOCALIZATION2DSERVER) << "Missing 'retrieve_position_periodically' parameter. Using default value: true. Period:" << m_period ;
145  }
146  else
147  {
148  m_getdata_using_periodic_thread = general_group.find("retrieve_position_periodically").asBool();
150  { yCInfo(LOCALIZATION2DSERVER) << "retrieve_position_periodically requested, Period:" << m_period; }
151  else
152  { yCInfo(LOCALIZATION2DSERVER) << "retrieve_position_periodically NOT requested. Localization data obtained asynchronously."; }
153  }
154 
155 
156  m_local_name = "/localizationServer";
157  if (!general_group.check("name"))
158  {
159  yCInfo(LOCALIZATION2DSERVER) << "Missing 'name' parameter. Using default value: /localizationServer";
160  }
161  else
162  {
163  m_local_name = general_group.find("name").asString();
164  if (m_local_name.c_str()[0] != '/') { yCError(LOCALIZATION2DSERVER) << "Missing '/' in name parameter" ; return false; }
165  yCInfo(LOCALIZATION2DSERVER) << "Using local name:" << m_local_name;
166  }
167 
168  m_rpcPortName = m_local_name + "/rpc";
169  m_2DLocationPortName = m_local_name + "/streaming:o";
170  m_odometryPortName = m_local_name + "/odometry:o";
171 
172  if (config.check("subdevice"))
173  {
174  Property p;
175  PolyDriverList driverlist;
176  p.fromString(config.toString(), false);
177  p.put("device", config.find("subdevice").asString());
178 
179  if (!pLoc.open(p) || !pLoc.isValid())
180  {
181  yCError(LOCALIZATION2DSERVER) << "Failed to open subdevice.. check params";
182  return false;
183  }
184 
185  driverlist.push(&pLoc, "1");
186  if (!attachAll(driverlist))
187  {
188  yCError(LOCALIZATION2DSERVER) << "Failed to open subdevice.. check params";
189  return false;
190  }
191  }
192  else
193  {
194  yCInfo(LOCALIZATION2DSERVER) << "Waiting for device to attach";
195  }
197 
198  if (!initialize_YARP(config))
199  {
200  yCError(LOCALIZATION2DSERVER) << "Error initializing YARP ports";
201  return false;
202  }
203 
204  if (!initialize_ROS(config))
205  {
206  yCError(LOCALIZATION2DSERVER) << "Error initializing ROS system";
207  return false;
208  }
209 
210  return true;
211 }
212 
214 {
215  if (params.check("ROS"))
216  {
217  Bottle& ros_group = params.findGroup("ROS");
218  if (ros_group.check("publish_tf"))
219  {
221  }
222  if (ros_group.check("publish_odom"))
223  {
225  }
226 
227  if (!ros_group.check("parent_frame_id"))
228  {
229  yCError(LOCALIZATION2DSERVER) << "Missing 'parent_frame_id' parameter";
230  //return false;
231  }
232  else
233  {
234  m_parent_frame_id = ros_group.find("parent_frame_id").asString();
235  }
236  if (!ros_group.check("child_frame_id"))
237  {
238  yCError(LOCALIZATION2DSERVER) << "Missing 'child_frame_id' parameter";
239  //return false;
240  }
241  else
242  {
243  m_child_frame_id = ros_group.find("child_frame_id").asString();
244  }
245 
246  }
247  else
248  {
249  yCInfo(LOCALIZATION2DSERVER) << "ROS initialization not requested";
250  return true;
251  }
252 
253  if (m_ros_node == nullptr)
254  {
255  bool b= false;
256  m_ros_node = new yarp::os::Node(m_local_name+"_ROSnode");
257  if (m_ros_node == nullptr)
258  {
259  yCError(LOCALIZATION2DSERVER) << "Opening " << m_local_name << " Node, check your yarp-ROS network configuration";
260  }
261 
262  string ros_odom_topic = m_local_name + string("/odom");
263  b = m_odometry_publisher.topic(ros_odom_topic);
264  if (!b)
265  {
266  yCError(LOCALIZATION2DSERVER) << "Unable to publish data on" << ros_odom_topic << "topic";
267  }
268  b = m_tf_publisher.topic("/tf");
269  if (!b)
270  {
271  yCError(LOCALIZATION2DSERVER) << "Unable to publish data on /tf topic";
272  }
273  yCInfo(LOCALIZATION2DSERVER) << "ROS initialized";
274  }
275  return true;
276 }
277 
279 {
281  {
282  yCError(LOCALIZATION2DSERVER, "Failed to open port %s", m_2DLocationPortName.c_str());
283  return false;
284  }
285 
286  if (!m_odometryPort.open(m_odometryPortName.c_str()))
287  {
288  yCError(LOCALIZATION2DSERVER, "Failed to open port %s", m_odometryPortName.c_str());
289  return false;
290  }
291 
292  if (!m_rpcPort.open(m_rpcPortName.c_str()))
293  {
294  yCError(LOCALIZATION2DSERVER, "Failed to open port %s", m_rpcPortName.c_str());
295  return false;
296  }
297  m_rpcPort.setReader(*this);
298 
299  return true;
300 }
301 
303 {
304  yCTrace(LOCALIZATION2DSERVER, "Close");
305  if (PeriodicThread::isRunning())
306  {
307  PeriodicThread::stop();
308  }
309 
310  detachAll();
311 
317  m_rpcPort.close();
318 
319  if (m_ros_node)
320  {
323  delete m_ros_node;
324  m_ros_node = nullptr;
325  }
326 
327  yCDebug(LOCALIZATION2DSERVER) << "Execution terminated";
328  return true;
329 }
330 
332 {
333  yarp::os::Bottle command;
334  yarp::os::Bottle reply;
335  bool ok = command.read(connection);
336  if (!ok) return false;
337 
338  reply.clear();
339 
340  if (command.get(0).isVocab())
341  {
342  if (command.get(0).asVocab() == VOCAB_INAVIGATION && command.get(1).isVocab())
343  {
344  int request = command.get(1).asVocab();
345  if (request == VOCAB_NAV_GET_CURRENT_POS)
346  {
348  {
349  //m_current_position is obtained by run()
350  reply.addVocab(VOCAB_OK);
355  }
356  else
357  {
358  //m_current_position is obtained by getCurrentPosition()
360  reply.addVocab(VOCAB_OK);
365  }
366  }
367  else if (request == VOCAB_NAV_SET_INITIAL_POS)
368  {
369  Map2DLocation init_loc;
370  init_loc.map_id = command.get(2).asString();
371  init_loc.x = command.get(3).asFloat64();
372  init_loc.y = command.get(4).asFloat64();
373  init_loc.theta = command.get(5).asFloat64();
374  iLoc->setInitialPose(init_loc);
375  reply.addVocab(VOCAB_OK);
376  }
377  else if (request == VOCAB_NAV_GET_CURRENT_POSCOV)
378  {
379  Map2DLocation init_loc;
380  yarp::sig::Matrix cov(3, 3);
381  iLoc->getCurrentPosition(init_loc, cov);
382  reply.addVocab(VOCAB_OK);
387  yarp::os::Bottle& mc = reply.addList();
388  for (size_t i = 0; i < 3; i++) { for (size_t j = 0; j < 3; j++) { mc.addFloat64(cov[i][j]); } }
389  }
390  else if (request == VOCAB_NAV_SET_INITIAL_POSCOV)
391  {
392  Map2DLocation init_loc;
393  yarp::sig::Matrix cov(3,3);
394  init_loc.map_id = command.get(2).asString();
395  init_loc.x = command.get(3).asFloat64();
396  init_loc.y = command.get(4).asFloat64();
397  init_loc.theta = command.get(5).asFloat64();
398  Bottle* mc = command.get(6).asList();
399  if (mc!=nullptr && mc->size() == 9)
400  {
401  for (size_t i = 0; i < 3; i++) { for (size_t j = 0; j < 3; j++) { cov[i][j] = mc->get(i * 3 + j).asFloat64(); } }
402  bool ret = iLoc->setInitialPose(init_loc, cov);
403  if (ret) { reply.addVocab(VOCAB_OK); }
404  else { reply.addVocab(VOCAB_ERR); }
405  }
406  else
407  {
408  reply.addVocab(VOCAB_ERR);
409  }
410  }
411  else if (request == VOCAB_NAV_LOCALIZATION_START)
412  {
414  reply.addVocab(VOCAB_OK);
415  }
416  else if (request == VOCAB_NAV_LOCALIZATION_STOP)
417  {
419  reply.addVocab(VOCAB_OK);
420  }
421  else if (request == VOCAB_NAV_GET_LOCALIZER_STATUS)
422  {
424  {
425  //m_current_status is obtained by run()
426  reply.addVocab(VOCAB_OK);
427  reply.addVocab(m_current_status);
428  }
429  else
430  {
431  //m_current_status is obtained by getLocalizationStatus()
433  reply.addVocab(VOCAB_OK);
434  reply.addVocab(m_current_status);
435  }
436  }
437  else if (request == VOCAB_NAV_GET_LOCALIZER_POSES)
438  {
439  std::vector<Map2DLocation> poses;
440  iLoc->getEstimatedPoses(poses);
441  reply.addVocab(VOCAB_OK);
442  reply.addInt32(poses.size());
443  for (size_t i=0; i<poses.size(); i++)
444  {
445  Bottle& b = reply.addList();
446  b.addString(poses[i].map_id);
447  b.addFloat64(poses[i].x);
448  b.addFloat64(poses[i].y);
449  b.addFloat64(poses[i].theta);
450  }
451  }
452  else
453  {
454  reply.addVocab(VOCAB_ERR);
455  }
456  }
457  else
458  {
459  yCError(LOCALIZATION2DSERVER) << "Invalid vocab received";
460  reply.addVocab(VOCAB_ERR);
461  }
462  }
463  else if (command.get(0).isString() && command.get(0).asString() == "help")
464  {
465  reply.addVocab(Vocab::encode("many"));
466  reply.addString("Available commands are:");
467  reply.addString("getLoc");
468  reply.addString("initLoc <map_name> <x> <y> <angle in degrees>");
469  }
470  else if (command.get(0).isString() && command.get(0).asString() == "getLoc")
471  {
472  Map2DLocation curr_loc;
473  iLoc->getCurrentPosition(curr_loc);
474  std::string s = std::string("Current Location is: ") + curr_loc.toString();
475  reply.addString(s);
476  }
477  else if (command.get(0).isString() && command.get(0).asString() == "initLoc")
478  {
479  Map2DLocation init_loc;
480  init_loc.map_id = command.get(1).asString();
481  init_loc.x = command.get(2).asFloat64();
482  init_loc.y = command.get(3).asFloat64();
483  init_loc.theta = command.get(4).asFloat64();
484  iLoc->setInitialPose(init_loc);
485  std::string s = std::string("Localization initialized to: ") + init_loc.toString();
486  reply.addString(s);
487  }
488  else
489  {
490  yCError(LOCALIZATION2DSERVER) << "Invalid command type";
491  reply.addVocab(VOCAB_ERR);
492  }
493 
494  yarp::os::ConnectionWriter *returnToSender = connection.getWriter();
495  if (returnToSender != nullptr)
496  {
497  reply.write(*returnToSender);
498  }
499 
500  return true;
501 }
502 
504 {
505  double m_stats_time_curr = yarp::os::Time::now();
506  if (m_stats_time_curr - m_stats_time_last > 5.0)
507  {
508  yCInfo(LOCALIZATION2DSERVER) << "Running";
510  }
511 
513  {
515  if (ret == false)
516  {
517  yCError(LOCALIZATION2DSERVER) << "getLocalizationStatus() failed";
518  }
519 
521  {
522  //update the stamp
523 
524 
526  if (ret2 == false)
527  {
528  yCError(LOCALIZATION2DSERVER) << "getCurrentPosition() failed";
529  }
530  else
531  {
533  }
535  if (ret3 == false)
536  {
537  //yCError(LOCALIZATION2DSERVER) << "getEstimatedOdometry() failed";
538  }
539  else
540  {
542  }
543  }
544  else
545  {
546  yCWarning(LOCALIZATION2DSERVER, "The system is not properly localized!");
547  }
548  }
549 
550  if (1) publish_odometry_on_yarp_port();
551  if (1) publish_2DLocation_on_yarp_port();
552  if (m_ros_publish_odometry_on_topic) publish_odometry_on_ROS_topic();
553  if (m_ros_publish_odometry_on_tf) publish_odometry_on_TF_topic();
554 
555 }
556 
557 void Localization2DServer::publish_odometry_on_yarp_port()
558 {
559  if (m_odometryPort.getOutputCount() > 0)
560  {
562  odom = m_current_odometry;
563 
564  //send data to port
567  }
568 }
569 
570 void Localization2DServer::publish_2DLocation_on_yarp_port()
571 {
573  {
576  {
577  loc = m_current_position;
578  }
579  else
580  {
581  Map2DLocation temp_loc;
582  temp_loc.x = std::nan("");
583  temp_loc.y = std::nan("");
584  temp_loc.theta = std::nan("");
585  loc = temp_loc;
586  }
587 
588  //send data to port
591  }
592 }
593 
594 void Localization2DServer::publish_odometry_on_TF_topic()
595 {
598  transform.child_frame_id = m_child_frame_id;
599  transform.header.frame_id = m_parent_frame_id;
600  transform.header.seq = m_odom_stamp.getCount();
601  transform.header.stamp = m_odom_stamp.getTime();
602  double halfYaw = m_current_odometry.odom_theta / 180.0 * M_PI * 0.5;
603  double cosYaw = cos(halfYaw);
604  double sinYaw = sin(halfYaw);
605  transform.transform.rotation.x = 0;
606  transform.transform.rotation.y = 0;
607  transform.transform.rotation.z = sinYaw;
608  transform.transform.rotation.w = cosYaw;
611  transform.transform.translation.z = 0;
612  if (rosData.transforms.size() == 0)
613  {
614  rosData.transforms.push_back(transform);
615  }
616  else
617  {
618  rosData.transforms[0] = transform;
619  }
620 
622 }
623 
624 void Localization2DServer::publish_odometry_on_ROS_topic()
625 {
627  {
629  odom.clear();
631  odom.header.seq = m_odom_stamp.getCount();
632  odom.header.stamp = m_odom_stamp.getTime();
634 
637  odom.pose.pose.position.z = 0;
638  yarp::sig::Vector vecrpy(3);
639  vecrpy[0] = 0;
640  vecrpy[1] = 0;
641  vecrpy[2] = m_current_odometry.odom_theta;
642  yarp::sig::Matrix matrix = yarp::math::rpy2dcm(vecrpy);
644  odom.pose.pose.orientation.x = q.x();
645  odom.pose.pose.orientation.y = q.y();
646  odom.pose.pose.orientation.z = q.z();
647  odom.pose.pose.orientation.w = q.w();
648  //odom.pose.covariance = 0;
649 
652  odom.twist.twist.linear.z = 0;
653  odom.twist.twist.angular.x = 0;
654  odom.twist.twist.angular.y = 0;
656  //odom.twist.covariance = 0;
657 
659  }
660 }
yarp::os::Port::close
void close() override
Stop port activity.
Definition: Port.cpp:357
LogStream.h
yarp::rosmsg::geometry_msgs::Quaternion::y
yarp::conf::float64_t y
Definition: Quaternion.h:38
yarp::rosmsg::geometry_msgs::Vector3::z
yarp::conf::float64_t z
Definition: Vector3.h:42
yarp::os::Bottle
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:73
yarp::os::Publisher::close
void close() override
Stop port activity.
Definition: Publisher.h:88
yarp::os::Value::asVocab
virtual std::int32_t asVocab() const
Get vocabulary identifier as an integer.
Definition: Value.cpp:231
Localization2DServer::m_odometryPort
yarp::os::BufferedPort< yarp::dev::OdometryData > m_odometryPort
Definition: Localization2DServer.h:77
Localization2DServer::m_current_position
yarp::dev::Nav2D::Map2DLocation m_current_position
Definition: Localization2DServer.h:100
yarp::os::Property::put
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:998
yarp::os::Bottle::clear
void clear()
Empties the bottle of any objects it contains.
Definition: Bottle.cpp:124
Network.h
yarp::rosmsg::geometry_msgs::Point::z
yarp::conf::float64_t z
Definition: Point.h:37
yarp::dev::OdometryData::base_vel_theta
double base_vel_theta
angular velocity of the robot [deg/s] expressed in the robot reference frame
Definition: OdometryData.h:53
VOCAB_NAV_GET_CURRENT_POS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_CURRENT_POS
Definition: ILocalization2D.h:122
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
VOCAB_NAV_GET_LOCALIZER_POSES
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_LOCALIZER_POSES
Definition: ILocalization2D.h:130
yarp::math::Quaternion::fromRotationMatrix
void fromRotationMatrix(const yarp::sig::Matrix &R)
Converts a rotation matrix to a quaternion.
Definition: Quaternion.cpp:154
yarp::rosmsg::geometry_msgs::TransformStamped::transform
yarp::rosmsg::geometry_msgs::Transform transform
Definition: TransformStamped.h:45
yarp::os::Bottle::size
size_type size() const
Gets the number of elements in the bottle.
Definition: Bottle.cpp:254
Vector.h
contains the definition of a Vector type
yarp::dev::Map2DLocationData::y
double y
Definition: Map2DLocationData.h:32
Localization2DServer::detachAll
virtual bool detachAll() override
Detach the object (you must have first called attach).
Definition: Localization2DServer.cpp:108
yarp::math::Quaternion::y
double y() const
Definition: Quaternion.cpp:80
Localization2DServer::m_current_odometry
yarp::dev::OdometryData m_current_odometry
Definition: Localization2DServer.h:99
yarp::rosmsg::geometry_msgs::TwistWithCovariance::twist
yarp::rosmsg::geometry_msgs::Twist twist
Definition: TwistWithCovariance.h:41
yarp::os::Searchable::findGroup
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
yarp::rosmsg::geometry_msgs::Pose::position
yarp::rosmsg::geometry_msgs::Point position
Definition: Pose.h:36
yarp::dev::Nav2D::localization_status_not_yet_localized
@ localization_status_not_yet_localized
Definition: ILocalization2D.h:26
yCWarning
#define yCWarning(component,...)
Definition: LogComponent.h:146
yarp::rosmsg::geometry_msgs::TransformStamped
Definition: TransformStamped.h:41
Port.h
yarp::dev::OdometryData::base_vel_y
double base_vel_y
velocity of the robot [m/s] expressed in the robot reference frame
Definition: OdometryData.h:49
yarp::os::Searchable::toString
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
yarp::dev::Nav2D::Map2DLocation::toString
std::string toString() const
Returns text representation of the location.
Definition: Map2DLocation.h:77
yarp::os::Property::fromString
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1046
Localization2DServer::m_current_status
yarp::dev::Nav2D::LocalizationStatusEnum m_current_status
Definition: Localization2DServer.h:101
yarp::math::Quaternion::z
double z() const
Definition: Quaternion.cpp:85
yarp::dev::PolyDriverList::size
int size() const
Definition: PolyDriverList.cpp:39
yarp::dev::PolyDriver::isValid
bool isValid() const
Check if device is valid.
Definition: PolyDriver.cpp:199
Localization2DServer::m_stats_time_last
double m_stats_time_last
Definition: Localization2DServer.h:93
YARP_LOG_COMPONENT
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
yarp::rosmsg::geometry_msgs::Vector3::y
yarp::conf::float64_t y
Definition: Vector3.h:41
yarp::rosmsg::std_msgs::Header::frame_id
std::string frame_id
Definition: Header.h:49
yarp::rosmsg::tf2_msgs::TFMessage::transforms
std::vector< yarp::rosmsg::geometry_msgs::TransformStamped > transforms
Definition: TFMessage.h:33
Localization2DServer::m_period
double m_period
Definition: Localization2DServer.h:94
Localization2DServer::m_getdata_using_periodic_thread
bool m_getdata_using_periodic_thread
Definition: Localization2DServer.h:97
yarp::os::Port::getOutputCount
int getOutputCount() override
Determine how many output connections this port has.
Definition: Port.cpp:561
yarp::rosmsg::geometry_msgs::PoseWithCovariance::pose
yarp::rosmsg::geometry_msgs::Pose pose
Definition: PoseWithCovariance.h:41
M_PI
#define M_PI
Definition: Localization2DServer.cpp:46
yarp::os::BufferedPort::interrupt
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: BufferedPort-inl.h:82
yarp::rosmsg::geometry_msgs::Vector3::x
yarp::conf::float64_t x
Definition: Vector3.h:40
yarp::os::BufferedPort::setEnvelope
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
Definition: BufferedPort-inl.h:232
yarp::dev::Nav2D::LocalizationStatusEnum
LocalizationStatusEnum
Definition: ILocalization2D.h:25
yarp::rosmsg::geometry_msgs::Quaternion::x
yarp::conf::float64_t x
Definition: Quaternion.h:37
yarp::dev::DeviceDriver::view
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:77
Localization2DServer::read
virtual bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Localization2DServer.cpp:331
Localization2DServer::m_ros_publish_odometry_on_topic
bool m_ros_publish_odometry_on_topic
Definition: Localization2DServer.h:68
yarp::os::Port::open
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: Port.cpp:82
yarp::rosmsg::geometry_msgs::Transform::rotation
yarp::rosmsg::geometry_msgs::Quaternion rotation
Definition: Transform.h:38
ret
bool ret
Definition: ImplementAxisInfo.cpp:72
Localization2DServer.h
yarp::rosmsg::geometry_msgs::Pose::orientation
yarp::rosmsg::geometry_msgs::Quaternion orientation
Definition: Pose.h:37
Localization2DServer::m_rpcPort
yarp::os::Port m_rpcPort
Definition: Localization2DServer.h:73
DEFAULT_THREAD_PERIOD
#define DEFAULT_THREAD_PERIOD
Definition: Localization2DServer.cpp:43
yarp::dev::PolyDriverList
Definition: PolyDriverList.h:22
ControlBoardInterfaces.h
define control board standard interfaces
yarp::os::Bottle::addFloat64
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
Definition: Bottle.cpp:161
yarp::dev::PolyDriver::open
bool open(const std::string &txt)
Construct and configure a device by its common name.
Definition: PolyDriver.cpp:143
yarp::dev::Map2DLocationData::theta
double theta
Definition: Map2DLocationData.h:33
Localization2DServer::iLoc
yarp::dev::Nav2D::ILocalization2D * iLoc
Definition: Localization2DServer.h:91
yarp::os::Bottle::find
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Bottle.cpp:290
yarp::os::Time::now
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:124
yarp::dev
An interface for the device drivers.
Definition: audioBufferSizeData.cpp:17
Localization2DServer::m_local_name
std::string m_local_name
Definition: Localization2DServer.h:72
yarp::dev::OdometryData
Definition: OdometryData.h:27
yarp::dev::OdometryData::base_vel_x
double base_vel_x
velocity of the robot [m/s] expressed in the robot reference frame
Definition: OdometryData.h:45
Localization2DServer::m_ros_node
yarp::os::Node * m_ros_node
Definition: Localization2DServer.h:85
yarp::math::rpy2dcm
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:818
Localization2DServer::run
virtual void run() override
Loop function.
Definition: Localization2DServer.cpp:503
Localization2DServer::m_rpcPortName
std::string m_rpcPortName
Definition: Localization2DServer.h:74
yarp::dev::PolyDriverList::push
void push(PolyDriver *p, const char *k)
Definition: PolyDriverList.cpp:44
yarp::os::BufferedPort::prepare
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::BufferedPort::write.
Definition: BufferedPort-inl.h:114
yarp::math::Quaternion::x
double x() const
Definition: Quaternion.cpp:75
yarp::sig::VectorOf< double >
Localization2DServer::m_odometry_publisher
yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry > m_odometry_publisher
Definition: Localization2DServer.h:86
yarp::os::Bottle::check
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Bottle.cpp:280
yarp::os::BufferedPort::getOutputCount
int getOutputCount() override
Determine how many output connections this port has.
Definition: BufferedPort-inl.h:251
yarp::rosmsg::std_msgs::Header::seq
std::uint32_t seq
Definition: Header.h:47
yarp::dev::Nav2D::ILocalization2D::getEstimatedOdometry
virtual bool getEstimatedOdometry(yarp::dev::OdometryData &odom)=0
Gets the estimated odometry the robot, including its velocity expressed in the world and in the local...
yarp::os::Value::isString
virtual bool isString() const
Checks if value is a string.
Definition: Value.cpp:159
Localization2DServer::pLoc
yarp::dev::PolyDriver pLoc
Definition: Localization2DServer.h:90
Localization2DServer::m_fixed_frame
std::string m_fixed_frame
Definition: Localization2DServer.h:80
yarp::dev::Nav2D::localization_status_localized_ok
@ localization_status_localized_ok
Definition: ILocalization2D.h:27
yarp::rosmsg::nav_msgs::Odometry
Definition: Odometry.h:39
yarp::os::Publisher::topic
bool topic(const std::string &name)
Set topic to publish to.
Definition: Publisher.h:67
yarp::dev::Nav2D::ILocalization2D::startLocalizationService
virtual bool startLocalizationService()=0
Starts the localization service.
yarp::os::Bottle::get
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:249
Localization2DServer::m_odometryPortName
std::string m_odometryPortName
Definition: Localization2DServer.h:78
yarp::os::Bottle::addList
Bottle & addList()
Places an empty nested list in the bottle, at the end of the list.
Definition: Bottle.cpp:185
yarp::os::Publisher::write
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:152
yarp::os::Bottle::write
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
Definition: Bottle.cpp:233
Math.h
yarp::os::ConnectionWriter
An interface for writing to a network connection.
Definition: ConnectionWriter.h:40
yarp::rosmsg::geometry_msgs::Twist::linear
yarp::rosmsg::geometry_msgs::Vector3 linear
Definition: Twist.h:35
Localization2DServer::m_2DLocationPortName
std::string m_2DLocationPortName
Definition: Localization2DServer.h:76
PolyDriver.h
yarp::rosmsg::geometry_msgs::Transform::translation
yarp::rosmsg::geometry_msgs::Vector3 translation
Definition: Transform.h:37
IMap2D.h
yarp::dev::OdometryData::odom_theta
double odom_theta
orientation the robot [deg], expressed in the world reference frame
Definition: OdometryData.h:41
Localization2DServer::m_robot_frame
std::string m_robot_frame
Definition: Localization2DServer.h:79
Localization2DServer::m_loc_stamp
yarp::os::Stamp m_loc_stamp
Definition: Localization2DServer.h:95
yarp::os::Stamp::getTime
double getTime() const
Get the time stamp.
Definition: Stamp.cpp:37
Localization2DServer::initialize_ROS
bool initialize_ROS(yarp::os::Searchable &config)
Definition: Localization2DServer.cpp:213
yarp::os::Value::asBool
virtual bool asBool() const
Get boolean value.
Definition: Value.cpp:189
yarp::os::Value::asString
virtual std::string asString() const
Get string value.
Definition: Value.cpp:237
yarp::dev::PolyDriver
A container for a device driver.
Definition: PolyDriver.h:27
yarp::os::BufferedPort::open
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: BufferedPort-inl.h:41
VOCAB_NAV_GET_LOCALIZER_STATUS
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_LOCALIZER_STATUS
Definition: ILocalization2D.h:129
yarp::os::Searchable::check
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
VOCAB_NAV_LOCALIZATION_START
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCALIZATION_START
Definition: ILocalization2D.h:126
yarp::rosmsg::nav_msgs::Odometry::pose
yarp::rosmsg::geometry_msgs::PoseWithCovariance pose
Definition: Odometry.h:43
yarp::os::Searchable::find
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
yarp::os::Bottle::addInt32
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
Definition: Bottle.cpp:143
yarp::os::Vocab::encode
NetInt32 encode(const std::string &str)
Convert a string into a vocabulary identifier.
Definition: Vocab.cpp:14
yarp::os::Node
The Node class.
Definition: Node.h:27
yarp::math::Quaternion
Definition: Quaternion.h:27
yarp::os::Stamp::getCount
int getCount() const
Get the sequence number.
Definition: Stamp.cpp:32
RFModule.h
yarp::rosmsg::nav_msgs::Odometry::child_frame_id
std::string child_frame_id
Definition: Odometry.h:42
yarp::os::ConnectionReader::getWriter
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
yarp::rosmsg::geometry_msgs::Quaternion::w
yarp::conf::float64_t w
Definition: Quaternion.h:40
yarp::rosmsg::geometry_msgs::Twist::angular
yarp::rosmsg::geometry_msgs::Vector3 angular
Definition: Twist.h:36
yarp::dev::Nav2D
Definition: ILocalization2D.h:21
yarp::os::Bottle::addString
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition: Bottle.cpp:173
yarp::rosmsg::nav_msgs::Odometry::twist
yarp::rosmsg::geometry_msgs::TwistWithCovariance twist
Definition: Odometry.h:44
yarp::os::Port::setReader
void setReader(PortReader &reader) override
Set an external reader for port data.
Definition: Port.cpp:505
VOCAB_NAV_SET_INITIAL_POSCOV
constexpr yarp::conf::vocab32_t VOCAB_NAV_SET_INITIAL_POSCOV
Definition: ILocalization2D.h:125
yarp::os::PeriodicThread
An abstraction for a periodic thread.
Definition: PeriodicThread.h:25
Localization2DServer::m_odom_stamp
yarp::os::Stamp m_odom_stamp
Definition: Localization2DServer.h:96
yarp::os::Publisher::asPort
Port & asPort() override
Get the concrete Port being used for communication.
Definition: Publisher.h:172
yarp::os::Bottle::addVocab
void addVocab(int x)
Places a vocabulary item in the bottle, at the end of the list.
Definition: Bottle.cpp:167
VOCAB_NAV_GET_CURRENT_POSCOV
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_CURRENT_POSCOV
Definition: ILocalization2D.h:124
LogComponent.h
yarp::dev::Nav2D::ILocalization2D::stopLocalizationService
virtual bool stopLocalizationService()=0
Stops the localization service.
VOCAB_ERR
constexpr yarp::conf::vocab32_t VOCAB_ERR
Definition: GenericVocabs.h:20
yarp::dev::Nav2D::Map2DLocation
Definition: Map2DLocation.h:30
yarp::dev::Nav2D::ILocalization2D::setInitialPose
virtual bool setInitialPose(const yarp::dev::Nav2D::Map2DLocation &loc)=0
Sets the initial pose for the localization algorithm which estimates the current position of the robo...
yarp::os::ConnectionReader
An interface for reading from a network connection.
Definition: ConnectionReader.h:40
yarp::rosmsg::tf2_msgs::TFMessage
Definition: TFMessage.h:31
Localization2DServer::open
virtual bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
Definition: Localization2DServer.cpp:118
yCError
#define yCError(component,...)
Definition: LogComponent.h:157
yarp::rosmsg::geometry_msgs::Quaternion::z
yarp::conf::float64_t z
Definition: Quaternion.h:39
yarp::math::Quaternion::w
double w() const
Definition: Quaternion.cpp:70
yarp::rosmsg::geometry_msgs::TransformStamped::header
yarp::rosmsg::std_msgs::Header header
Definition: TransformStamped.h:43
yarp::rosmsg::nav_msgs::Odometry::clear
void clear()
Definition: Odometry.h:54
yarp::os::Stamp::update
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition: Stamp.cpp:113
Localization2DServer::Localization2DServer
Localization2DServer()
Definition: Localization2DServer.cpp:55
yarp::os::BufferedPort::write
void write(bool forceStrict=false)
Write the current object being returned by BufferedPort::prepare.
Definition: BufferedPort-inl.h:126
yCInfo
#define yCInfo(component,...)
Definition: LogComponent.h:135
yarp::rosmsg::geometry_msgs::Point::y
yarp::conf::float64_t y
Definition: Point.h:36
yarp::dev::Nav2D::ILocalization2D::getLocalizationStatus
virtual bool getLocalizationStatus(LocalizationStatusEnum &status)=0
Gets the current status of the localization task.
yarp::os
An interface to the operating system, including Port based communication.
Definition: AbstractCarrier.h:17
yCDebug
#define yCDebug(component,...)
Definition: LogComponent.h:112
yarp::rosmsg::nav_msgs::Odometry::header
yarp::rosmsg::std_msgs::Header header
Definition: Odometry.h:41
yarp::dev::OdometryData::odom_y
double odom_y
position of the robot [m], expressed in the world reference frame
Definition: OdometryData.h:37
yarp::os::BufferedPort::close
void close() override
Stop port activity.
Definition: BufferedPort-inl.h:73
yarp::os::Bottle::read
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
Definition: Bottle.cpp:243
yarp::dev::OdometryData::odom_x
double odom_x
position of the robot [m], expressed in the world reference frame
Definition: OdometryData.h:33
yarp::os::Port::interrupt
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: Port.cpp:377
yarp::os::Value::asList
virtual Bottle * asList() const
Get list value.
Definition: Value.cpp:243
Time.h
yarp::dev::Map2DLocationData::x
double x
Definition: Map2DLocationData.h:31
yCTrace
#define yCTrace(component,...)
Definition: LogComponent.h:88
Localization2DServer::m_2DLocationPort
yarp::os::BufferedPort< yarp::dev::Nav2D::Map2DLocation > m_2DLocationPort
Definition: Localization2DServer.h:75
Localization2DServer::attachAll
virtual bool attachAll(const yarp::dev::PolyDriverList &l) override
Attach to a list of objects.
Definition: Localization2DServer.cpp:67
yarp::dev::Nav2D::ILocalization2D::getCurrentPosition
virtual bool getCurrentPosition(yarp::dev::Nav2D::Map2DLocation &loc)=0
Gets the current position of the robot w.r.t world reference frame.
VOCAB_NAV_LOCALIZATION_STOP
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCALIZATION_STOP
Definition: ILocalization2D.h:127
Localization2DServer::m_parent_frame_id
std::string m_parent_frame_id
Definition: Localization2DServer.h:84
Localization2DServer::m_tf_publisher
yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage > m_tf_publisher
Definition: Localization2DServer.h:87
yarp::dev::Map2DLocationData::map_id
std::string map_id
Definition: Map2DLocationData.h:30
yarp::os::Value::asFloat64
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:225
yarp::dev::Nav2D::ILocalization2D::getEstimatedPoses
virtual bool getEstimatedPoses(std::vector< yarp::dev::Nav2D::Map2DLocation > &poses)=0
Gets a set of pose estimates computed by the localization algorithm.
yarp::rosmsg::std_msgs::Header::stamp
yarp::rosmsg::TickTime stamp
Definition: Header.h:48
Bottle.h
VOCAB_OK
constexpr yarp::conf::vocab32_t VOCAB_OK
Definition: GenericVocabs.h:18
VOCAB_INAVIGATION
constexpr yarp::conf::vocab32_t VOCAB_INAVIGATION
Definition: ILocalization2D.h:110
IFrameTransform.h
yarp::os::Value::isVocab
virtual bool isVocab() const
Checks if value is a vocabulary identifier.
Definition: Value.cpp:177
VOCAB_NAV_SET_INITIAL_POS
constexpr yarp::conf::vocab32_t VOCAB_NAV_SET_INITIAL_POS
Definition: ILocalization2D.h:123
yarp::os::Property
A class for storing options and configuration information.
Definition: Property.h:37
Localization2DServer::m_ros_publish_odometry_on_tf
bool m_ros_publish_odometry_on_tf
Definition: Localization2DServer.h:69
yarp::os::Publisher::prepare
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
Definition: Publisher.h:127
Localization2DServer::m_child_frame_id
std::string m_child_frame_id
Definition: Localization2DServer.h:83
Localization2DServer::initialize_YARP
bool initialize_YARP(yarp::os::Searchable &config)
Definition: Localization2DServer.cpp:278
Localization2DServer::close
virtual bool close() override
Close the DeviceDriver.
Definition: Localization2DServer.cpp:302
yarp::rosmsg::geometry_msgs::TransformStamped::child_frame_id
std::string child_frame_id
Definition: TransformStamped.h:44
yarp::rosmsg::geometry_msgs::Point::x
yarp::conf::float64_t x
Definition: Point.h:35
yarp::sig::Matrix
A class for a Matrix.
Definition: Matrix.h:46