6#define _USE_MATH_DEFINES
23 m_odometry2D_interface =
nullptr;
32 driver->
view(m_odometry2D_interface);
35 if (m_odometry2D_interface ==
nullptr)
43 bool b = PeriodicThread::start();
51 if (PeriodicThread::isRunning())
53 PeriodicThread::stop();
55 m_odometry2D_interface =
nullptr;
69 if (!config.
check(
"period"))
76 if (!config.
check(
"name"))
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";
91 if(config.
check(
"subdevice"))
111 if (!m_rpcPort.
open(m_rpcPortName))
118 if (!m_port_odometer.
open(m_odometerStreamingPortName))
124 if (!m_port_odometry.
open(m_odometryStreamingPortName))
130 if (!m_port_velocity.
open(m_velocityStreamingPortName))
136 PeriodicThread::setPeriod(m_period);
143 m_port_velocity.
close();
145 m_port_odometry.
close();
147 m_port_odometer.
close();
152 if (m_odometry2D_interface!=
nullptr)
155 double synchronized_timestamp = 0;
156 m_odometry2D_interface->
getOdometry(odometryData, &synchronized_timestamp);
158 if (std::isnan(synchronized_timestamp) ==
false)
160 m_lastStateStamp.
update(synchronized_timestamp);
180 m_port_odometry.
write();
187 odometer_data.
clear();
188 double traveled_distance = sqrt((odometryData.
odom_vel_x - m_oldOdometryData.
odom_x) *
195 m_port_odometer.
write();
203 velocityData.
clear();
207 m_port_velocity.
write();
222 bool b = m_RPC.
read(connection);
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 ¶ms) 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.
bool isValid() const
Check if device is valid.
bool open(const std::string &txt)
Construct and configure a device by its common name.
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.
A class for storing options and configuration information.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
A base class for nested structures that can be searched.
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...
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual std::string asString() const
Get string value.
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(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.