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

Subscriber not seeing cmd_vel messages

asked 2014-02-15 03:59:01 -0500

MarkyMark2012 gravatar image

updated 2014-02-15 21:51:04 -0500

Hi,

I've written a node with publishes (Successfully) and subscribes to cmd_vel messages. Problem I'm getting is that the call back is never being called. C++ code is very simple, as per tutorial - abridged version below:

#include <ros/ros.h>
#include <sensor_msgs/JointState.h>
#include <sensor_msgs/Range.h>
#include <sensor_msgs/LaserScan.h>
#include <diagnostic_updater/diagnostic_updater.h>
#include <std_msgs/Bool.h>
#include <diagnostic_updater/publisher.h>
#include <geometry_msgs/Twist.h>

// For moving the robot on the map
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>

#include "Consts.h" 
#include "RobotInterface.h"
#include "NetworkInterface.h"

void cmd_vel_callback(const geometry_msgs::Twist& vel_cmd)
{ 
ROS_INFO("I heard: [%s]", vel_cmd.linear.y);
cout << "Twist Received " << endl;
}

int main( int argc, char* argv[] )
{
ros::init(argc, argv, "toeminator_publisher" );

ros::NodeHandle n_("~");
ros::NodeHandle n("");
ros::NodeHandle lSubscriber("");
ros::NodeHandle nIR("");
ros::NodeHandle nLaser("");
ros::Rate loop_rate(10);
    ros::Subscriber sub = lSubscriber.subscribe("/cmd_vel", 1000, cmd_vel_callback);

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

RobotData lRobotData;

while( n.ok() ) 
{
    ros::spin();
}

return 1;
}

The python publisher is basically the turtlebot's keyboard publisher and running rtq_graph shows the message link between the publisher and subscriber as expected (below) and "rostopic echo /cmd_vel" shows the message flowing

image description

Not sure where I've gone wrong here. Would welcome any pointers.

Kind Regards

Mark

EDIT: Updated with full code. Also I neglected to mention (apologies) that the roscore and the C++ processes are running on a different machine to where the teleop keyboard process is running. That said publishing from the roscore machine to rviz etc on the telop machine is working with out issue (ROS_IP is set to the IP addresses of the respective machines - as mentioned in the networking setup tutorials)

edit retag flag offensive close merge delete

Comments

Can you please copy the rest of the code? That can help

Pedro_85 gravatar image Pedro_85  ( 2014-02-15 10:26:28 -0500 )edit

3 Answers

Sort by » oldest newest most voted
0

answered 2014-02-28 21:53:25 -0500

MarkyMark2012 gravatar image

Ok so found the problem. Whilst the ROS_IP addresses were set correctly I'm running the heavy weight ROS side on a virtual box and the sensor/actuator side on rasp pi. It was the network setup of the VM it was set to NAT - changed it to bridged. Now all is well.

Thanks

Mark

edit flag offensive delete link more
1

answered 2014-02-16 05:59:02 -0500

Pedro_85 gravatar image

updated 2014-02-16 05:59:21 -0500

Based on the fact that when you run rostopic echo /cmd_vel you are able to get the information, I created a basic version of your code and it seems to be working for me:

#include <ros/ros.h>
#include <geometry_msgs/Twist.h>

void cmd_vel_callback(const geometry_msgs::Twist& vel_cmd)
{ 
    ROS_INFO("I heard: [%f]", vel_cmd.linear.y);
    std::cout << "Twist Received " << std::endl;
}


int main( int argc, char* argv[] )
{
ros::init(argc, argv, "toeminator_publisher" );

ros::NodeHandle n;
ros::Subscriber sub = n.subscribe("/cmd_vel", 1000, cmd_vel_callback);

while( n.ok() ) 
{
    ros::spin();
}

return 1;
}

I changed ROS_INFO("I heard: [%s]", vel_cmd.linear.y); to ROS_INFO("I heard: [%f]", vel_cmd.linear.y); because it was giving me an Segmentation fault error message. Make sure you have added the geometry_msgs to your dependencies. I hope this helps. Good luck!

edit flag offensive delete link more

Comments

Hi - Thanks for the help. I've had a chance to play around with this some more.It seem to have something to do with the fact that I'm running across two machines. Running roscore on the same machine and it all works.Put roscore on another machine (With ROS_IP set) then nothing. Although ros_topic and rqt_graph see everything

MarkyMark2012 gravatar image MarkyMark2012  ( 2014-02-26 09:26:46 -0500 )edit
0

answered 2014-02-15 11:34:38 -0500

As already requested by in comments, posting complete code would be helpful (Edit your original posting for that). To do a shot in the dark: What you describe could happen if your subscriber object is destroyed before your loop with ros::spin() is reached. Can´t tell if that´s the case from the abridged version you posted so far, though.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2014-02-15 03:59:01 -0500

Seen: 4,787 times

Last updated: Feb 28 '14