6#define _USE_MATH_DEFINES
23 m_odometry2D_interface =
nullptr;
32 driver->
view(m_odometry2D_interface);
37 if (m_odometry2D_interface ==
nullptr)
43 PeriodicThread::setPeriod(m_period);
44 return PeriodicThread::start();
50 if (PeriodicThread::isRunning())
52 PeriodicThread::stop();
54 m_odometry2D_interface =
nullptr;
68 if (config.
check(
"publish_tf_topic")) {
69 m_enable_publish_tf =
true;
71 if (config.
check(
"skip_tf_topic")) {
72 m_enable_publish_tf =
false;
75 if (!config.
check(
"period")) {
78 m_period = config.
find(
"period").asFloat64();
81 if (!config.
check(
"node_name")) {
85 m_nodeName = config.
find(
"node_name").asString();
86 if (m_nodeName[0] !=
'/') {
91 if (!config.
check(
"topic_name")) {
95 m_topicName = config.
find(
"topic_name").asString();
96 if (m_topicName[0] !=
'/') {
101 if (!config.
check(
"odom_frame")) {
105 m_odomFrame = config.
find(
"odom_frame").asString();
108 if (!config.
check(
"base_frame")) {
112 m_baseFrame = config.
find(
"base_frame").asString();
115 if (m_node ==
nullptr) {
119 if (!rosPublisherPort_odometry.
topic(m_topicName)) {
124 if (m_enable_publish_tf)
126 if (!rosPublisherPort_tf.
topic(
"/tf")) {
140 if (m_odometry2D_interface!=
nullptr)
143 double synchronized_timestamp = 0;
144 m_odometry2D_interface->
getOdometry(odometryData, &synchronized_timestamp);
146 if (std::isnan(synchronized_timestamp) ==
false)
148 m_lastStateStamp.
update(synchronized_timestamp);
157 yarp::rosmsg::nav_msgs::Odometry& rosData = rosPublisherPort_odometry.
prepare();
158 rosData.header.seq = m_lastStateStamp.
getCount();
159 rosData.header.stamp = m_lastStateStamp.
getTime();
160 rosData.header.frame_id = m_odomFrame;
161 rosData.child_frame_id = m_baseFrame;
163 rosData.pose.pose.position.x = odometryData.
odom_x;
164 rosData.pose.pose.position.y = odometryData.
odom_y;
165 rosData.pose.pose.position.z = 0.0;
166 yarp::rosmsg::geometry_msgs::Quaternion odom_quat;
168 double cosYaw = cos(halfYaw);
169 double sinYaw = sin(halfYaw);
172 odom_quat.z = sinYaw;
173 odom_quat.w = cosYaw;
174 rosData.pose.pose.orientation = odom_quat;
175 rosData.twist.twist.linear.x = odometryData.
base_vel_x;
176 rosData.twist.twist.linear.y = odometryData.
base_vel_y;
177 rosData.twist.twist.linear.z = 0;
178 rosData.twist.twist.angular.x = 0;
179 rosData.twist.twist.angular.y = 0;
181 rosPublisherPort_odometry.
write();
184 if (m_enable_publish_tf)
186 yarp::rosmsg::tf2_msgs::TFMessage& rosData = rosPublisherPort_tf.
prepare();
187 yarp::rosmsg::geometry_msgs::TransformStamped transform;
188 transform.header.frame_id = m_odomFrame;
189 transform.child_frame_id = m_baseFrame;
190 transform.header.seq = m_lastStateStamp.
getCount();
191 transform.header.stamp = m_lastStateStamp.
getTime();
193 double cosYaw = cos(halfYaw);
194 double sinYaw = sin(halfYaw);
195 transform.transform.rotation.x = 0;
196 transform.transform.rotation.y = 0;
197 transform.transform.rotation.z = sinYaw;
198 transform.transform.rotation.w = cosYaw;
199 transform.transform.translation.x = odometryData.
odom_x;
200 transform.transform.translation.y = odometryData.
odom_y;
201 transform.transform.translation.z = 0;
202 if (rosData.transforms.size() == 0)
204 rosData.transforms.push_back(transform);
206 else if (rosData.transforms.size() == 1)
208 rosData.transforms[0] = transform;
214 rosPublisherPort_tf.
write();
225 if (PeriodicThread::isRunning())
227 PeriodicThread::stop();
234 rosPublisherPort_odometry.
close();
235 if (m_enable_publish_tf)
237 rosPublisherPort_tf.
close();
const yarp::os::LogComponent & ODOMETRY2D_NWS_ROS()
#define DEFAULT_THREAD_PERIOD
Odometry2D_nws_ros: A ros nws to get odometry and publish it on a ros topic. The attached device must...
bool open(yarp::os::Searchable ¶ms) override
Open the DeviceDriver.
bool detach() override
Detach the object (you must have first called attach).
bool threadInit() override
Initialization method.
void run() override
Loop function.
void threadRelease() override
Release method.
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
bool close() override
Close the DeviceDriver.
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 base_vel_theta
angular velocity of the robot [deg/s] expressed in the robot 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
A container for a device driver.
bool isValid() const
Check if device is valid.
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 close() override
Stop port activity.
bool topic(const std::string &name)
Set topic to publish to.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
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...
double getTime() const
Get the time stamp.
int getCount() const
Get the sequence number.
#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.