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
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 if (!this->parseParams(config)) { return false; }
67
68 m_rpcPortName = m_name + "/rpc";
69 m_odometerStreamingPortName = m_name + "/odometer:o";
70 m_odometryStreamingPortName = m_name + "/odometry:o";
71 m_velocityStreamingPortName = m_name + "/velocity:o";
72
73 //open rpc port
74 if (!m_rpcPort.open(m_rpcPortName))
75 {
76 yCError(ODOMETRY2D_NWS_YARP, "Failed to open port %s", m_rpcPortName.c_str());
77 return false;
78 }
79 m_rpcPort.setReader(*this);
80
81 if (!m_port_odometer.open(m_odometerStreamingPortName))
82 {
83 yCError(ODOMETRY2D_NWS_YARP, "failed to open port %s", m_odometerStreamingPortName.c_str());
84 return false;
85 }
86
87 if (!m_port_odometry.open(m_odometryStreamingPortName))
88 {
89 yCError(ODOMETRY2D_NWS_YARP, "failed to open port %s", m_odometryStreamingPortName.c_str());
90 return false;
91 }
92
93 if (!m_port_velocity.open(m_velocityStreamingPortName))
94 {
95 yCError(ODOMETRY2D_NWS_YARP, "failed to open port %s", m_velocityStreamingPortName.c_str());
96 return false;
97 }
98
99 PeriodicThread::setPeriod(m_period);
100
101 yCInfo(ODOMETRY2D_NWS_YARP) << "Waiting for device to attach";
102
103 return true;
104}
105
107{
108 m_port_velocity.interrupt();
109 m_port_velocity.close();
110 m_port_odometry.interrupt();
111 m_port_odometry.close();
112 m_port_odometer.interrupt();
113 m_port_odometer.close();
114}
115
117{
118 if (m_odometry2D_interface!=nullptr)
119 {
120 yarp::dev::OdometryData odometryData;
121 double synchronized_timestamp = 0;
122 m_odometry2D_interface->getOdometry(odometryData, &synchronized_timestamp);
123
124 if (std::isnan(synchronized_timestamp) == false)
125 {
126 m_lastStateStamp.update(synchronized_timestamp);
127 }
128 else
129 {
130 m_lastStateStamp.update(yarp::os::Time::now());
131 }
132
133 if (m_port_odometry.getOutputCount()>0)
134 {
135 m_port_odometry.setEnvelope(m_lastStateStamp);
136 yarp::dev::OdometryData &odometryDataFromPort = m_port_odometry.prepare();
137 odometryDataFromPort.odom_x= odometryData.odom_x; //position in the odom reference frame
138 odometryDataFromPort.odom_y= odometryData.odom_y;
139 odometryDataFromPort.odom_theta= odometryData.odom_theta;
140 odometryDataFromPort.base_vel_x= odometryData.base_vel_x; //velocity in the robot reference frame
141 odometryDataFromPort.base_vel_y= odometryData.base_vel_y;
142 odometryDataFromPort.base_vel_theta= odometryData.base_vel_theta;
143 odometryDataFromPort.odom_vel_x= odometryData.odom_vel_x; //velocity in the odom reference frame
144 odometryDataFromPort.odom_vel_y= odometryData.odom_vel_y;
145 odometryDataFromPort.odom_vel_theta= odometryData.odom_vel_theta;
146 m_port_odometry.write();
147 }
148
149 if (m_port_odometer.getOutputCount()>0)
150 {
151 m_port_odometer.setEnvelope(m_lastStateStamp);
152 yarp::os::Bottle &odometer_data = m_port_odometer.prepare();
153 odometer_data.clear();
154 double traveled_distance = sqrt((odometryData.odom_vel_x - m_oldOdometryData.odom_x) *
155 (odometryData.odom_vel_x - m_oldOdometryData.odom_x) +
156 (odometryData.odom_vel_y - m_oldOdometryData.odom_y) *
157 (odometryData.odom_vel_y - m_oldOdometryData.odom_y));
158 double traveled_angle = odometryData.odom_theta - m_oldOdometryData.odom_theta;
159 odometer_data.addFloat64(traveled_distance);
160 odometer_data.addFloat64(traveled_angle);
161 m_port_odometer.write();
162 }
163
164
165 if (m_port_velocity.getOutputCount()>0)
166 {
167 m_port_velocity.setEnvelope(m_lastStateStamp);
168 yarp::os::Bottle &velocityData = m_port_velocity.prepare();
169 velocityData.clear();
170 velocityData.addFloat64(sqrt(odometryData.odom_vel_x * odometryData.odom_vel_x +
171 odometryData.odom_vel_y * odometryData.odom_vel_y));
172 velocityData.addFloat64(odometryData.base_vel_theta);
173 m_port_velocity.write();
174 }
175 } else {
176 yCError(ODOMETRY2D_NWS_YARP) << "no yarp::dev::Nav2D::IOdometry2D interface found";
177 }
178}
179
181{
182 yCTrace(ODOMETRY2D_NWS_YARP, "Odometry2D_nws_yarp::Close");
183 return detach();
184}
185
186bool Odometry2D_nws_yarp::read(yarp::os::ConnectionReader& connection)
187{
188 bool b = m_RPC.read(connection);
189 if (b)
190 {
191 return true;
192 }
193 yCDebug(ODOMETRY2D_NWS_YARP) << "read() Command failed";
194 return false;
195}
#define DEFAULT_THREAD_PERIOD
const yarp::os::LogComponent & ODOMETRY2D_NWS_YARP()
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
void setInterface(yarp::dev::Nav2D::IOdometry2D *_odom)
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 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
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.
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