ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

how make an odom publisher in cpp

asked 2020-10-13 13:29:54 -0500

reavers92 gravatar image

updated 2022-07-10 12:18:43 -0500

lucasw gravatar image

Hi everyone, i'm trying to create an odom node that takes the input data from <geometry_msgs twist.h="">. my problem is that i am not familiar with cpp so i have no idea how to make these. I thought I'd subscribe to <geometry_msgs twist.h=""> in a separate tread and populate the msg.linear.x and msg.angular.z values ​​into global variables and then use them in the While loop for delta_x and delta_th computation, but I have no idea how to proceed or if I need to change the method. How can i do? below I have reported the code, (my environment is ros melodic). Thanks everyone for the help

#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
#include <geometry_msgs/Twist.h>

int main(int argc, char** argv){
    ros::init(argc, argv, "odometry_publisher");

    ros::NodeHandle n;
    ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50);
    tf::TransformBroadcaster odom_broadcaster;



    double x = 0.0;
    double y = 0.0;
    double th = 0.0;

    double vx = 0.1;
    double vy = 0.0;
    double vth = 0.1;

    ros::Time current_time, last_time;
    current_time = ros::Time::now();
    last_time = ros::Time::now();

    ros::Rate r(1.0);
    while(n.ok()){
        current_time = ros::Time::now();

        //compute odometry in a typical way given the velocities of the robot
        double dt = (current_time - last_time).toSec();
        double delta_x = (vx * cos(th) - vy * sin(th)) * dt;
        double delta_y = (vx * sin(th) + vy * cos(th)) * dt;
        double delta_th = vth * dt;

        x += delta_x;           
        y += delta_y;           
        th += delta_th;

        //since all odometry is 6DOF we'll need a quaternion created from yaw
        geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);

        //first, we'll publish the transform over tf
        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;

        //send the transform
        odom_broadcaster.sendTransform(odom_trans);

        //next, we'll publish the odometry message over ROS
        nav_msgs::Odometry odom;
        odom.header.stamp = current_time;
        odom.header.frame_id = "odom";

        //set the position
        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;

        //set the velocity
        odom.child_frame_id = "base_link";
        odom.twist.twist.linear.x = vx;
        odom.twist.twist.linear.y = vy;
        odom.twist.twist.angular.z = vth;

        //publish the message
        odom_pub.publish(odom);

        last_time = current_time;
        r.sleep();
        }
    }
edit retag flag offensive close merge delete

Comments

It is supposed to be while(ros::ok()){...}I believe. Also put the subscriber in this same file . Maybe take a look at this tutorial and then come back with more specific questions/error messages

JackB gravatar image JackB  ( 2020-10-13 16:09:00 -0500 )edit

1 Answer

Sort by » oldest newest most voted
0

answered 2020-10-14 10:53:38 -0500

miura gravatar image

I think it's more common to use subscribers instead of threads, as mentioned in the comments. I'll share an example code fragment for your reference.

// global variables definition
double vx;
double vy;
double vth;

// add callback function
void callback_function(const geometry_msgs::Twist::ConstPtr& msg)
{
    vx = msg->linear.x;
    vy = 0.0;
    vth = msg->angular.z;
}

int main(int argc, char** argv){
// ...
    double x = 0.0;
    double y = 0.0;
    double th = 0.0;

    // add subscribe defenition
    ros::Subscriber sub = n.subscribe("twist_topic", 1, callback_function);

    // initialize global variables
    vx = 0.0;
    vy = 0.0;
    vth = 0.0;

    ros::Time current_time, last_time;
// ...
    last_time = current_time;
    ros::spinOnce();  // enable callback
    r.sleep();
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-10-13 13:29:54 -0500

Seen: 1,749 times

Last updated: Oct 14 '20