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

Odometry causing a segmentation error

asked 2021-07-15 09:07:26 -0500

iopoi97 gravatar image

updated 2021-07-15 18:34:32 -0500

Good afternoon, I have to control a differential drive robot. I had not to use the differential controller plugin, so i just implemented two velocity controllers and a joint state. I now have to compute odometry for my robot and I want to use my joint state as a velocity sensor for each wheel. So i would subscribe /joint_state, take the two velocities and the compute odometry from them and publish all on a /odom topic. The building works, but once i run this script in my ros network I have just some loops and then a core dump error when the callback is called. Could you help me, please? Here is my header file:

#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
#include <sensor_msgs/JointState.h>
#include <math.h>
#include "boost/thread.hpp"
#include "tf/tf.h"
using namespace std;

class ODOM{
    public:
        ODOM();
        void run();
        void encoders_sub_callback (sensor_msgs::JointState msg);
        void compute_odom ();

    private:
    ros::NodeHandle _nh;
         float _wl;
         float _wr;
        long double _x;
        long double _y;
        long double _th;
        bool _first_odom;

        ros::Subscriber _encoders_sub;
        ros::Publisher _odom_pub;

};

and here my cpp file:

#include "odom.h"

ODOM::ODOM(){
    _encoders_sub = _nh.subscribe("joint_states", 1, &ODOM::encoders_sub_callback, this);
    _odom_pub = _nh.advertise<nav_msgs::Odometry>("/odom",1);
    _wl=0.0;
    _wr=0.0;
    _x=0.0;
    _y=0.0;
    _th=0.0;
    _first_odom=false;
}

//here it happens the segmentation fault

void ODOM::encoders_sub_callback(sensor_msgs::JointState msg){
    cout<<"callback"<<endl;
    _wl= msg.velocity[0];
    cout<<_wl<<endl;
    _wr=msg.velocity[1];
    cout<<_wr<<endl;
}

//the computing odom function//...

... and then...

void ODOM::run(){

    boost::thread odom_t( &ODOM::compute_odom, this);

    ros::spin();
}

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

    ODOM odom;
    odom.run();


    return 0;
}
edit retag flag offensive close merge delete

Comments

please!! It's very important

iopoi97 gravatar image iopoi97  ( 2021-07-15 16:00:08 -0500 )edit

@iopoi97 Please don't make noise to try to get responses. It's considered bad etiquette. Please see our support guidelines: http://wiki.ros.org/Support

The more help you can provide the easier it is to help you. Have you tried to get a backtrace from the crash? Have you tried attaching a debugger? Have you tried disabling parts of your system to isolate which line is causing the problem? The more you can isolate the problem the easier it is for someone to understand what your mistake is. Right now you've dumped a lot of code here without enough information to fully reproduce your problem so if someone is going to try to help you they need to read through all the code, and then guess at what assumptions your making and how your setting up your environment. Then take an educated guess at the problem.

The ...(more)

tfoote gravatar image tfoote  ( 2021-07-15 16:15:18 -0500 )edit

I'm very sorry. I debugged just printing messages between code lines. As said the segmentation fault happens when the encoders_sub_callback is called. I edited my post suppressing the compute odometry part. it's a simple Runge Kutta integration on the heading and steering velocities retrieved from the left and right wheels velocities.

iopoi97 gravatar image iopoi97  ( 2021-07-15 18:39:21 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2021-07-15 19:27:41 -0500

Change this code to:

void ODOM::encoders_sub_callback(sensor_msgs::JointState msg){
    if (msg.velocity.size() < 2) return;

    cout<<"callback"<<endl;
    _wl= msg.velocity[0];
    cout<<_wl<<endl;
    _wr=msg.velocity[1];
    cout<<_wr<<endl;
}

Probably you're entering in this callback with some empty jointstate.

edit flag offensive delete link more

Comments

Thank you very much. Now it works!

iopoi97 gravatar image iopoi97  ( 2021-07-17 07:45:27 -0500 )edit
0

answered 2021-07-16 06:55:52 -0500

Mike Scheutzow gravatar image

updated 2021-07-16 06:58:00 -0500

  1. Maybe it's related to version of boost library, but I use boost::bind for thread create when calling a c++ method.
  2. In the example you've show, there is no need for a compute_odom() thread. Standard practice in roscpp is to call ros::spin() from main().
  3. I agree with @Teo Cardoso that you should check the length of the array before accessing it.
edit flag offensive delete link more

Comments

Thank you very much!!

iopoi97 gravatar image iopoi97  ( 2021-07-17 07:46:39 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-07-15 09:07:26 -0500

Seen: 177 times

Last updated: Jul 16 '21