YARP
Yet Another Robot Platform
Localization2DServer.h
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 #ifndef YARP_DEV_LOCALIZATION2DSERVER_H
20 #define YARP_DEV_LOCALIZATION2DSERVER_H
21 
22 
23 #include <yarp/os/Network.h>
24 #include <yarp/os/RFModule.h>
25 #include <yarp/os/Time.h>
26 #include <yarp/os/Port.h>
27 #include <yarp/os/Stamp.h>
28 #include <yarp/os/Node.h>
29 #include <yarp/os/Publisher.h>
30 #include <yarp/os/BufferedPort.h>
31 #include <yarp/os/PeriodicThread.h>
32 #include <yarp/dev/PolyDriver.h>
36 #include <yarp/dev/OdometryData.h>
39 #include <math.h>
40 
64 {
65 protected:
66 
67  //general options
70 
71  //yarp
72  std::string m_local_name;
74  std::string m_rpcPortName;
76  std::string m_2DLocationPortName;
78  std::string m_odometryPortName;
79  std::string m_robot_frame;
80  std::string m_fixed_frame;
81 
82  //ROS
83  std::string m_child_frame_id;
84  std::string m_parent_frame_id;
88 
89  //drivers and interfaces
92 
94  double m_period;
98 
102 
103 private:
104  void publish_2DLocation_on_yarp_port();
105  void publish_odometry_on_yarp_port();
106  void publish_odometry_on_ROS_topic();
107  void publish_odometry_on_TF_topic();
108 
109 public:
111 
112 public:
113  virtual bool open(yarp::os::Searchable& prop) override;
114  virtual bool close() override;
115  virtual bool detachAll() override;
116  virtual bool attachAll(const yarp::dev::PolyDriverList &l) override;
117  virtual void run() override;
118 
120  bool initialize_ROS(yarp::os::Searchable& config);
121  virtual bool read(yarp::os::ConnectionReader& connection) override;
122 };
123 
124 #endif // YARP_DEV_LOCALIZATION2DSERVER_H
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
Network.h
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
Localization2DServer
localization2DServer: A localization server which can be wrap multiple algorithms and devices to prov...
Definition: Localization2DServer.h:64
Localization2DServer::detachAll
virtual bool detachAll() override
Detach the object (you must have first called attach).
Definition: Localization2DServer.cpp:108
Localization2DServer::m_current_odometry
yarp::dev::OdometryData m_current_odometry
Definition: Localization2DServer.h:99
Port.h
Localization2DServer::m_current_status
yarp::dev::Nav2D::LocalizationStatusEnum m_current_status
Definition: Localization2DServer.h:101
Localization2DServer::m_stats_time_last
double m_stats_time_last
Definition: Localization2DServer.h:93
yarp::dev::DeviceDriver
Interface implemented by all device drivers.
Definition: DeviceDriver.h:38
yarp::dev::Nav2D::ILocalization2D
ILocalization2D interface.
Definition: ILocalization2D.h:40
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::dev::Nav2D::LocalizationStatusEnum
LocalizationStatusEnum
Definition: ILocalization2D.h:25
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
TFMessage.h
Localization2DServer::m_rpcPort
yarp::os::Port m_rpcPort
Definition: Localization2DServer.h:73
yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry >
yarp::dev::PolyDriverList
Definition: PolyDriverList.h:22
ControlBoardInterfaces.h
define control board standard interfaces
Localization2DServer::iLoc
yarp::dev::Nav2D::ILocalization2D * iLoc
Definition: Localization2DServer.h:91
Localization2DServer::m_local_name
std::string m_local_name
Definition: Localization2DServer.h:72
yarp::dev::OdometryData
Definition: OdometryData.h:27
Localization2DServer::m_ros_node
yarp::os::Node * m_ros_node
Definition: Localization2DServer.h:85
Localization2DServer::run
virtual void run() override
Loop function.
Definition: Localization2DServer.cpp:503
Localization2DServer::m_rpcPortName
std::string m_rpcPortName
Definition: Localization2DServer.h:74
Localization2DServer::m_odometry_publisher
yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry > m_odometry_publisher
Definition: Localization2DServer.h:86
yarp::os::Port
A mini-server for network communication.
Definition: Port.h:50
yarp::os::BufferedPort< yarp::dev::Nav2D::Map2DLocation >
Localization2DServer::pLoc
yarp::dev::PolyDriver pLoc
Definition: Localization2DServer.h:90
Localization2DServer::m_fixed_frame
std::string m_fixed_frame
Definition: Localization2DServer.h:80
yarp::os::PortReader
Interface implemented by all objects that can read themselves from the network, such as Bottle object...
Definition: PortReader.h:28
Localization2DServer::m_odometryPortName
std::string m_odometryPortName
Definition: Localization2DServer.h:78
Localization2DServer::m_2DLocationPortName
std::string m_2DLocationPortName
Definition: Localization2DServer.h:76
PolyDriver.h
Stamp.h
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
Localization2DServer::initialize_ROS
bool initialize_ROS(yarp::os::Searchable &config)
Definition: Localization2DServer.cpp:213
yarp::dev::PolyDriver
A container for a device driver.
Definition: PolyDriver.h:27
Node.h
yarp::os::Node
The Node class.
Definition: Node.h:27
RFModule.h
BufferedPort.h
IMultipleWrapper.h
Odometry.h
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
PeriodicThread.h
ILocalization2D.h
yarp::dev::Nav2D::Map2DLocation
Definition: Map2DLocation.h:30
yarp::os::ConnectionReader
An interface for reading from a network connection.
Definition: ConnectionReader.h:40
yarp::os::Stamp
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
Localization2DServer::open
virtual bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
Definition: Localization2DServer.cpp:118
Localization2DServer::Localization2DServer
Localization2DServer()
Definition: Localization2DServer.cpp:55
Publisher.h
yarp::dev::IMultipleWrapper
Interface for an object that can wrap/attach to to another.
Definition: IMultipleWrapper.h:30
Time.h
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
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
Localization2DServer::m_ros_publish_odometry_on_tf
bool m_ros_publish_odometry_on_tf
Definition: Localization2DServer.h:69
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
OdometryData.h
Localization2DServer::close
virtual bool close() override
Close the DeviceDriver.
Definition: Localization2DServer.cpp:302