6#define _USE_MATH_DEFINES
23 m_odometry2D_interface =
nullptr;
29 std::lock_guard lock(m_mutex);
33 driver->
view(m_odometry2D_interface);
36 if (m_odometry2D_interface ==
nullptr)
42 m_RPC= std::make_unique<IOdometry2DRPCd>(m_odometry2D_interface);
44 bool b = PeriodicThread::start();
52 std::lock_guard lock(m_mutex);
54 if (PeriodicThread::isRunning())
56 PeriodicThread::stop();
58 m_odometry2D_interface =
nullptr;
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";
77 if (!m_rpcPort.
open(m_rpcPortName))
84 if (!m_port_odometer.
open(m_odometerStreamingPortName))
90 if (!m_port_odometry.
open(m_odometryStreamingPortName))
96 if (!m_port_velocity.
open(m_velocityStreamingPortName))
102 PeriodicThread::setPeriod(
m_period);
112 m_port_velocity.
close();
114 m_port_odometry.
close();
116 m_port_odometer.
close();
121 std::lock_guard lock(m_mutex);
123 if (m_odometry2D_interface!=
nullptr)
126 double synchronized_timestamp = 0;
127 m_odometry2D_interface->
getOdometry(odometryData, &synchronized_timestamp);
129 if (std::isnan(synchronized_timestamp) ==
false)
131 m_lastStateStamp.
update(synchronized_timestamp);
151 m_port_odometry.
write();
158 odometer_data.
clear();
159 double traveled_distance = sqrt((odometryData.
odom_vel_x - m_oldOdometryData.
odom_x) *
166 m_port_odometer.
write();
174 velocityData.
clear();
178 m_port_velocity.
write();
193 if (!connection.
isValid()) {
return false;}
194 if (!m_RPC) {
return false;}
196 std::lock_guard<std::mutex> lock(m_mutex);
199 bool b = m_RPC->read(connection);
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 ¶ms) 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.
bool isValid() const
Check if device is valid.
A simple collection of objects that can be described and transmitted in a portable way.
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
void clear()
Empties the bottle of any objects it contains.
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.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
#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.
The main, catch-all namespace for YARP.