YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
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
20
22{
23 m_odometry2D_interface = nullptr;
24}
25
26
28{
29 std::lock_guard lock(m_mutex);
30
31 if (driver->isValid())
32 {
33 driver->view(m_odometry2D_interface);
34 }
35
36 if (m_odometry2D_interface == nullptr)
37 {
38 yCError(ODOMETRY2D_NWS_YARP, "Subdevice passed to attach method is invalid");
39 return false;
40 }
41
42 m_RPC= std::make_unique<IOdometry2DRPCd>(m_odometry2D_interface);
43
44 bool b = PeriodicThread::start();
45
46 return b;
47}
48
49
51{
52 std::lock_guard lock(m_mutex);
53
54 if (PeriodicThread::isRunning())
55 {
56 PeriodicThread::stop();
57 }
58 m_odometry2D_interface = nullptr;
59 return true;
60}
61
63{
64 return true;
65}
66
68{
69 if (!this->parseParams(config)) { return false; }
70
71 m_rpcPortName = m_name + "/rpc";
72 m_odometerStreamingPortName = m_name + "/odometer:o";
73 m_odometryStreamingPortName = m_name + "/odometry:o";
74 m_velocityStreamingPortName = m_name + "/velocity:o";
75
76 //open rpc port
77 if (!m_rpcPort.open(m_rpcPortName))
78 {
79 yCError(ODOMETRY2D_NWS_YARP, "Failed to open port %s", m_rpcPortName.c_str());
80 return false;
81 }
82 m_rpcPort.setReader(*this);
83
84 if (!m_port_odometer.open(m_odometerStreamingPortName))
85 {
86 yCError(ODOMETRY2D_NWS_YARP, "failed to open port %s", m_odometerStreamingPortName.c_str());
87 return false;
88 }
89
90 if (!m_port_odometry.open(m_odometryStreamingPortName))
91 {
92 yCError(ODOMETRY2D_NWS_YARP, "failed to open port %s", m_odometryStreamingPortName.c_str());
93 return false;
94 }
95
96 if (!m_port_velocity.open(m_velocityStreamingPortName))
97 {
98 yCError(ODOMETRY2D_NWS_YARP, "failed to open port %s", m_velocityStreamingPortName.c_str());
99 return false;
100 }
101
102 PeriodicThread::setPeriod(m_period);
103
104 yCInfo(ODOMETRY2D_NWS_YARP) << "Waiting for device to attach";
105
106 return true;
107}
108
110{
111 m_port_velocity.interrupt();
112 m_port_velocity.close();
113 m_port_odometry.interrupt();
114 m_port_odometry.close();
115 m_port_odometer.interrupt();
116 m_port_odometer.close();
117}
118
120{
121 std::lock_guard lock(m_mutex);
122
123 if (m_odometry2D_interface!=nullptr)
124 {
125 yarp::dev::OdometryData odometryData;
126 double synchronized_timestamp = 0;
127 m_odometry2D_interface->getOdometry(odometryData, &synchronized_timestamp);
128
129 if (std::isnan(synchronized_timestamp) == false)
130 {
131 m_lastStateStamp.update(synchronized_timestamp);
132 }
133 else
134 {
135 m_lastStateStamp.update(yarp::os::Time::now());
136 }
137
138 if (m_port_odometry.getOutputCount()>0)
139 {
140 m_port_odometry.setEnvelope(m_lastStateStamp);
141 yarp::dev::OdometryData &odometryDataFromPort = m_port_odometry.prepare();
142 odometryDataFromPort.odom_x= odometryData.odom_x; //position in the odom reference frame
143 odometryDataFromPort.odom_y= odometryData.odom_y;
144 odometryDataFromPort.odom_theta= odometryData.odom_theta;
145 odometryDataFromPort.base_vel_x= odometryData.base_vel_x; //velocity in the robot reference frame
146 odometryDataFromPort.base_vel_y= odometryData.base_vel_y;
147 odometryDataFromPort.base_vel_theta= odometryData.base_vel_theta;
148 odometryDataFromPort.odom_vel_x= odometryData.odom_vel_x; //velocity in the odom reference frame
149 odometryDataFromPort.odom_vel_y= odometryData.odom_vel_y;
150 odometryDataFromPort.odom_vel_theta= odometryData.odom_vel_theta;
151 m_port_odometry.write();
152 }
153
154 if (m_port_odometer.getOutputCount()>0)
155 {
156 m_port_odometer.setEnvelope(m_lastStateStamp);
157 yarp::os::Bottle &odometer_data = m_port_odometer.prepare();
158 odometer_data.clear();
159 double traveled_distance = sqrt((odometryData.odom_vel_x - m_oldOdometryData.odom_x) *
160 (odometryData.odom_vel_x - m_oldOdometryData.odom_x) +
161 (odometryData.odom_vel_y - m_oldOdometryData.odom_y) *
162 (odometryData.odom_vel_y - m_oldOdometryData.odom_y));
163 double traveled_angle = odometryData.odom_theta - m_oldOdometryData.odom_theta;
164 odometer_data.addFloat64(traveled_distance);
165 odometer_data.addFloat64(traveled_angle);
166 m_port_odometer.write();
167 }
168
169
170 if (m_port_velocity.getOutputCount()>0)
171 {
172 m_port_velocity.setEnvelope(m_lastStateStamp);
173 yarp::os::Bottle &velocityData = m_port_velocity.prepare();
174 velocityData.clear();
175 velocityData.addFloat64(sqrt(odometryData.odom_vel_x * odometryData.odom_vel_x +
176 odometryData.odom_vel_y * odometryData.odom_vel_y));
177 velocityData.addFloat64(odometryData.base_vel_theta);
178 m_port_velocity.write();
179 }
180 } else {
181 yCError(ODOMETRY2D_NWS_YARP) << "no yarp::dev::Nav2D::IOdometry2D interface found";
182 }
183}
184
186{
187 yCTrace(ODOMETRY2D_NWS_YARP, "Odometry2D_nws_yarp::Close");
188 return detach();
189}
190
191bool Odometry2D_nws_yarp::read(yarp::os::ConnectionReader& connection)
192{
193 if (!connection.isValid()) { return false;}
194 if (!m_RPC) { return false;}
195
196 std::lock_guard<std::mutex> lock(m_mutex);
197 if (m_RPC)
198 {
199 bool b = m_RPC->read(connection);
200 if (b) {
201 return true;
202 }
203 }
204 yCDebug(ODOMETRY2D_NWS_YARP) << "read() Command failed";
205 return false;
206}
#define DEFAULT_THREAD_PERIOD
const yarp::os::LogComponent & ODOMETRY2D_NWS_YARP()
bool parseParams(const yarp::os::Searchable &config) override
Parse the DeviceDriver parameters.
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.
virtual yarp::dev::ReturnValue 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
double odom_vel_y
velocity of the robot [m/s] expressed in the world reference frame
double base_vel_theta
angular velocity of the robot [deg/s] expressed in the robot reference frame
double odom_vel_theta
angular velocity of the robot [deg/s] expressed in the world 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
double odom_vel_x
velocity of the robot [m/s] expressed in the world reference frame
A container for a device driver.
Definition PolyDriver.h:23
bool isValid() const
Check if device is valid.
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.
virtual bool isValid() const =0
A base class for nested structures that can be searched.
Definition Searchable.h:31
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition Stamp.cpp:124
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
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