cps_rmp220_support/nodes/odom_publisher.cpp

92 lines
2.4 KiB
C++
Raw Normal View History

2025-01-13 13:45:56 +00:00
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
2025-01-15 12:33:55 +00:00
double vx = 0.0;
double vy = 0.0;
double vth = 0.0;
void odomCallback(const nav_msgs::Odometry::ConstPtr& msg) {
// Extract velocity data from the /odom topic
vx = msg->twist.twist.linear.x;
vy = msg->twist.twist.linear.y;
vth = msg->twist.twist.angular.z;
}
int main(int argc, char** argv) {
2025-01-15 12:24:28 +00:00
ros::init(argc, argv, "odometry_publisher");
2025-01-13 13:45:56 +00:00
2025-01-15 12:24:28 +00:00
ros::NodeHandle n;
2025-01-15 12:33:55 +00:00
// Subscriber for /odom topic
ros::Subscriber odom_sub = n.subscribe("odom", 50, odomCallback);
// Publisher for odom topic
ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom_out", 50);
2025-01-15 12:24:28 +00:00
tf::TransformBroadcaster odom_broadcaster;
2025-01-13 13:45:56 +00:00
2025-01-15 12:24:28 +00:00
double x = 0.0;
double y = 0.0;
double th = 0.0;
2025-01-13 14:05:40 +00:00
2025-01-15 12:24:28 +00:00
ros::Time current_time, last_time;
current_time = ros::Time::now();
last_time = ros::Time::now();
2025-01-13 13:45:56 +00:00
2025-01-15 12:33:55 +00:00
ros::Rate r(50.0); // Update rate increased to 50 Hz
2025-01-13 13:45:56 +00:00
2025-01-15 12:33:55 +00:00
while (ros::ok()) {
ros::spinOnce(); // Check for incoming messages
2025-01-15 12:24:28 +00:00
current_time = ros::Time::now();
2025-01-13 13:45:56 +00:00
2025-01-15 12:33:55 +00:00
// Compute odometry based on subscribed velocity data
2025-01-15 12:24:28 +00:00
double dt = (current_time - last_time).toSec();
2025-01-15 12:48:25 +00:00
double delta_x = (vx * cos(th)) * dt;
double delta_y = (vx * sin(th)) * dt;
2025-01-15 12:24:28 +00:00
double delta_th = vth * dt;
2025-01-13 14:05:40 +00:00
2025-01-15 12:24:28 +00:00
x += delta_x;
y += delta_y;
th += delta_th;
2025-01-13 14:05:40 +00:00
2025-01-15 12:33:55 +00:00
// Create quaternion from yaw
2025-01-15 12:24:28 +00:00
geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);
2025-01-13 13:45:56 +00:00
2025-01-15 12:33:55 +00:00
// Publish the transform over tf
2025-01-15 12:24:28 +00:00
geometry_msgs::TransformStamped odom_trans;
odom_trans.header.stamp = current_time;
odom_trans.header.frame_id = "odom";
odom_trans.child_frame_id = "base_link";
odom_trans.transform.translation.x = x;
odom_trans.transform.translation.y = y;
odom_trans.transform.translation.z = 0.0;
odom_trans.transform.rotation = odom_quat;
odom_broadcaster.sendTransform(odom_trans);
2025-01-13 13:45:56 +00:00
2025-01-15 12:33:55 +00:00
// Publish the odometry message
2025-01-15 12:24:28 +00:00
nav_msgs::Odometry odom;
odom.header.stamp = current_time;
odom.header.frame_id = "odom";
2025-01-15 12:33:55 +00:00
// Set the position
2025-01-15 12:24:28 +00:00
odom.pose.pose.position.x = x;
odom.pose.pose.position.y = y;
odom.pose.pose.position.z = 0.0;
odom.pose.pose.orientation = odom_quat;
2025-01-15 12:33:55 +00:00
// Set the velocity
2025-01-15 12:24:28 +00:00
odom.child_frame_id = "base_link";
odom.twist.twist.linear.x = vx;
odom.twist.twist.linear.y = vy;
odom.twist.twist.angular.z = vth;
odom_pub.publish(odom);
last_time = current_time;
r.sleep();
}
2025-01-15 12:33:55 +00:00
}