YARP
Yet Another Robot Platform
Odometry2D_nws_yarp.cpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: LGPL-2.1-or-later
4 */
5
6#define _USE_MATH_DEFINES
7
10#include <yarp/os/LogStream.h>
11#include <yarp/os/Stamp.h>
12
13#include <cmath>
14
15YARP_LOG_COMPONENT(ODOMETRY2D_NWS_YARP, "yarp.devices.Odometry2D_nws_yarp")
16
18{
19}
20
22{
23 m_odometry2D_interface = nullptr;
24}
25
26
28{
29
30 if (driver->isValid())
31 {
32 driver->view(m_odometry2D_interface);
33 }
34
35 if (m_odometry2D_interface == nullptr)
36 {
37 yCError(ODOMETRY2D_NWS_YARP, "Subdevice passed to attach method is invalid");
38 return false;
39 }
40
41 m_RPC.setInterface(m_odometry2D_interface);
42
43 bool b = PeriodicThread::start();
44
45 return b;
46}
47
48
50{
51 if (PeriodicThread::isRunning())
52 {
53 PeriodicThread::stop();
54 }
55 m_odometry2D_interface = nullptr;
56 return true;
57}
58
60{
61 return true;
62}
63
65{
66 yarp::os::Property params;
67 params.fromString(config.toString());
68
69 if (!config.check("period"))
70 {
71 yCWarning(ODOMETRY2D_NWS_YARP) << "missing 'period' parameter, using default value of" << DEFAULT_THREAD_PERIOD;
72 } else {
73 m_period = config.find("period").asFloat64();
74 }
75
76 if (!config.check("name"))
77 {
78 yCInfo(ODOMETRY2D_NWS_YARP) << "Missing 'name' parameter. Using default value: " << m_local_name;
79 }
80 else
81 {
82 m_local_name = config.find("name").asString();
83 if (m_local_name.c_str()[0] != '/') { yCError(ODOMETRY2D_NWS_YARP) << "Missing '/' in name parameter"; return false; }
84 yCInfo(ODOMETRY2D_NWS_YARP) << "Using local name:" << m_local_name;
85 }
86 m_rpcPortName = m_local_name + "/rpc";
87 m_odometerStreamingPortName = m_local_name + "/odometer:o";
88 m_odometryStreamingPortName = m_local_name + "/odometry:o";
89 m_velocityStreamingPortName = m_local_name + "/velocity:o";
90
91 if(config.check("subdevice"))
92 {
94 p.fromString(config.toString(), false);
95 p.put("device", config.find("subdevice").asString());
96
97 if(!m_driver.open(p) || !m_driver.isValid())
98 {
99 yCError(ODOMETRY2D_NWS_YARP) << "failed to open subdevice.. check params";
100 return false;
101 }
102
103 if(!attach(&m_driver))
104 {
105 yCError(ODOMETRY2D_NWS_YARP) << "failed to open subdevice.. check params";
106 return false;
107 }
108 }
109
110 //open rpc port
111 if (!m_rpcPort.open(m_rpcPortName))
112 {
113 yCError(ODOMETRY2D_NWS_YARP, "Failed to open port %s", m_rpcPortName.c_str());
114 return false;
115 }
116 m_rpcPort.setReader(*this);
117
118 if (!m_port_odometer.open(m_odometerStreamingPortName))
119 {
120 yCError(ODOMETRY2D_NWS_YARP, "failed to open port %s", m_odometerStreamingPortName.c_str());
121 return false;
122 }
123
124 if (!m_port_odometry.open(m_odometryStreamingPortName))
125 {
126 yCError(ODOMETRY2D_NWS_YARP, "failed to open port %s", m_odometryStreamingPortName.c_str());
127 return false;
128 }
129
130 if (!m_port_velocity.open(m_velocityStreamingPortName))
131 {
132 yCError(ODOMETRY2D_NWS_YARP, "failed to open port %s", m_velocityStreamingPortName.c_str());
133 return false;
134 }
135
136 PeriodicThread::setPeriod(m_period);
137 return true;
138}
139
141{
142 m_port_velocity.interrupt();
143 m_port_velocity.close();
144 m_port_odometry.interrupt();
145 m_port_odometry.close();
146 m_port_odometer.interrupt();
147 m_port_odometer.close();
148}
149
151{
152 if (m_odometry2D_interface!=nullptr)
153 {
154 yarp::dev::OdometryData odometryData;
155 double synchronized_timestamp = 0;
156 m_odometry2D_interface->getOdometry(odometryData, &synchronized_timestamp);
157
158 if (std::isnan(synchronized_timestamp) == false)
159 {
160 m_lastStateStamp.update(synchronized_timestamp);
161 }
162 else
163 {
164 m_lastStateStamp.update(yarp::os::Time::now());
165 }
166
167 if (m_port_odometry.getOutputCount()>0)
168 {
169 m_port_odometry.setEnvelope(m_lastStateStamp);
170 yarp::dev::OdometryData &odometryDataFromPort = m_port_odometry.prepare();
171 odometryDataFromPort.odom_x= odometryData.odom_x; //position in the odom reference frame
172 odometryDataFromPort.odom_y= odometryData.odom_y;
173 odometryDataFromPort.odom_theta= odometryData.odom_theta;
174 odometryDataFromPort.base_vel_x= odometryData.base_vel_x; //velocity in the robot reference frame
175 odometryDataFromPort.base_vel_y= odometryData.base_vel_y;
176 odometryDataFromPort.base_vel_theta= odometryData.base_vel_theta;
177 odometryDataFromPort.odom_vel_x= odometryData.odom_vel_x; //velocity in the odom reference frame
178 odometryDataFromPort.odom_vel_y= odometryData.odom_vel_y;
179 odometryDataFromPort.odom_vel_theta= odometryData.odom_vel_theta;
180 m_port_odometry.write();
181 }
182
183 if (m_port_odometer.getOutputCount()>0)
184 {
185 m_port_odometer.setEnvelope(m_lastStateStamp);
186 yarp::os::Bottle &odometer_data = m_port_odometer.prepare();
187 odometer_data.clear();
188 double traveled_distance = sqrt((odometryData.odom_vel_x - m_oldOdometryData.odom_x) *
189 (odometryData.odom_vel_x - m_oldOdometryData.odom_x) +
190 (odometryData.odom_vel_y - m_oldOdometryData.odom_y) *
191 (odometryData.odom_vel_y - m_oldOdometryData.odom_y));
192 double traveled_angle = odometryData.odom_theta - m_oldOdometryData.odom_theta;
193 odometer_data.addFloat64(traveled_distance);
194 odometer_data.addFloat64(traveled_angle);
195 m_port_odometer.write();
196 }
197
198
199 if (m_port_velocity.getOutputCount()>0)
200 {
201 m_port_velocity.setEnvelope(m_lastStateStamp);
202 yarp::os::Bottle &velocityData = m_port_velocity.prepare();
203 velocityData.clear();
204 velocityData.addFloat64(sqrt(odometryData.odom_vel_x * odometryData.odom_vel_x +
205 odometryData.odom_vel_y * odometryData.odom_vel_y));
206 velocityData.addFloat64(odometryData.base_vel_theta);
207 m_port_velocity.write();
208 }
209 } else {
210 yCError(ODOMETRY2D_NWS_YARP) << "no yarp::dev::Nav2D::IOdometry2D interface found";
211 }
212}
213
215{
216 yCTrace(ODOMETRY2D_NWS_YARP, "Odometry2D_nws_yarp::Close");
217 return detach();
218}
219
220bool Odometry2D_nws_yarp::read(yarp::os::ConnectionReader& connection)
221{
222 bool b = m_RPC.read(connection);
223 if (b)
224 {
225 return true;
226 }
227 yCDebug(ODOMETRY2D_NWS_YARP) << "read() Command failed";
228 return false;
229}
const yarp::os::LogComponent & ODOMETRY2D_NWS_YARP()
constexpr double DEFAULT_THREAD_PERIOD
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
void setInterface(yarp::dev::Nav2D::IOdometry2D *_odom)
Odometry2D_nws_yarp: A yarp nws to get the odometry and publish it on 3 yarp ports:
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).
void run() override
Loop function.
bool threadInit() override
Initialization method.
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
void threadRelease() override
Release method.
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:88
virtual bool getOdometry(yarp::dev::OdometryData &odom, double *timestamp=nullptr)=0
Gets the odometry of the robot, including its velocity expressed in the world and in the local refere...
double base_vel_x
velocity of the robot [m/s] expressed in the robot reference frame
Definition: OdometryData.h:41
double odom_vel_y
velocity of the robot [m/s] expressed in the world reference frame
Definition: OdometryData.h:57
double base_vel_theta
angular velocity of the robot [deg/s] expressed in the robot reference frame
Definition: OdometryData.h:49
double odom_vel_theta
angular velocity of the robot [deg/s] expressed in the world reference frame
Definition: OdometryData.h:61
double base_vel_y
velocity of the robot [m/s] expressed in the robot reference frame
Definition: OdometryData.h:45
double odom_x
position of the robot [m], expressed in the world reference frame
Definition: OdometryData.h:29
double odom_y
position of the robot [m], expressed in the world reference frame
Definition: OdometryData.h:33
double odom_theta
orientation the robot [deg], expressed in the world reference frame
Definition: OdometryData.h:37
double odom_vel_x
velocity of the robot [m/s] expressed in the world reference frame
Definition: OdometryData.h:53
A container for a device driver.
Definition: PolyDriver.h:23
bool isValid() const
Check if device is valid.
Definition: PolyDriver.cpp:196
bool open(const std::string &txt)
Construct and configure a device by its common name.
Definition: PolyDriver.cpp:140
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.
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:64
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:158
void clear()
Empties the bottle of any objects it contains.
Definition: Bottle.cpp:121
void close() override
Stop port activity.
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
void interrupt() override
Interrupt any current reads or writes attached to the port.
int getOutputCount() override
Determine how many output connections this port has.
void write(bool forceStrict=false)
Write the current object being returned by BufferedPort::prepare.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::BufferedPort::write.
An interface for reading from a network connection.
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.
Definition: Property.cpp:1063
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:1015
A base class for nested structures that can be searched.
Definition: Searchable.h:63
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
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
#define yCInfo(component,...)
Definition: LogComponent.h:171
#define yCError(component,...)
Definition: LogComponent.h:213
#define yCTrace(component,...)
Definition: LogComponent.h:84
#define yCWarning(component,...)
Definition: LogComponent.h:192
#define yCDebug(component,...)
Definition: LogComponent.h:128
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:76
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:121
The main, catch-all namespace for YARP.
Definition: dirs.h:16