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

RViz displays "No messages received", what could be the reason?

asked 2012-10-11 05:07:15 -0500

tordalk gravatar image

updated 2012-10-11 22:12:34 -0500

Hi there, I have a code that goes like this and is very similar to an example code:

#include <ros/ros.h>
//#include <sensor_msgs/PointCloud2.h>
#include <pcl/ros/conversions.h>
#include <pcl_ros/point_cloud.h>
#include <pcl/point_types.h>
#include <iostream>
using namespace std;

ros::Publisher pub;

void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input){

  float x=0,y=0,z=0;
  pcl::PointCloud<pcl::PointXYZ>::Ptr msg (new pcl::PointCloud<pcl::PointXYZ>);
  msg->header.frame_id = "some_frame";
  msg->height = msg->width = 1;
  msg->points.push_back (pcl::PointXYZ(x, y, z));
  pub.publish (msg);
}

int main (int argc, char** argv){

   ros::init (argc, argv, "some_init");
   ros::NodeHandle nh;
   ros::Subscriber sub = nh.subscribe ("output", 100, cloud_cb);
   pub = nh.advertise<sensor_msgs::PointCloud2> ("output", 100);
   ros::Rate loop_rate(1);
   while (nh.ok()){
   ros::spin ();
   loop_rate.sleep ();}
}

Don't be concerned about the function's input argument. I just need this later as soon as I am able to process some incoming data, publish and then visualize it with RViz. So far, I'd like to see one single point when I'm using RViz. However, it indicates "No messages received". Does anyone know what the fault is? Kevin

edit retag flag offensive close merge delete

Comments

If possible, could you please edit your post and add the complete source code? As far as I can see, everything looks ok.

Lorenz gravatar image Lorenz  ( 2012-10-11 05:19:44 -0500 )edit

Hello Martin, thanks for your reply. I finally got your point with the triggering. Unfortunately when I run your code a problem with the transformation appears, stating : Transform [sender=/some_init] For frame [some_frame]: Frame [some_frame] does not exist. How can I fix that?

tordalk gravatar image tordalk  ( 2012-10-12 00:08:11 -0500 )edit
2

Don't use the frame id some_frame. That was just an example. Instead, use something that is present in your tf tree, for instance input->header.frame_id. Also, don't forget to set the stamp, e.g.: msg->header.stamp = input->header.stamp

Lorenz gravatar image Lorenz  ( 2012-10-12 04:34:02 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2012-10-11 23:14:20 -0500

updated 2012-10-12 05:21:47 -0500

Hi Kevin,

I think that the problem is that you are subscribing to the topic "output" and then you are publishing to the topic "output" again.

But, you publish to the topic "output" inside the callback of the subscriber to the topic "output" (cloud_cb). So, unless there is an external source pouring data into the topic "output", you will never trigger the callback (cloud_cb) and therefore, you will never publish anything. It is like a dog trying to bite its own tail :P

Even if you have an external source of content for the topic "output", I have never tried this kind of scenario, so I don't really know what behavior to expect. If you trigger the callback with a single external message to the topic "output" then you will get what you want, but maybe if there is an external continuous source of data for the topic "output" the amount of messages published and read again would grow exponentially? Not sure about this.

Probably this would work:

#include <ros/ros.h>
//#include <sensor_msgs/PointCloud2.h>
#include <pcl/ros/conversions.h>
#include <pcl_ros/point_cloud.h>
#include <pcl/point_types.h>
#include <iostream>
using namespace std;

ros::Publisher pub;

void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input){

  float x=0,y=0,z=0;
  pcl::PointCloud<pcl::PointXYZ>::Ptr msg (new pcl::PointCloud<pcl::PointXYZ>);
  msg->header.frame_id = "some_frame";
  msg->height = msg->width = 1;
  msg->points.push_back (pcl::PointXYZ(x, y, z));
  pub.publish (msg);
}

int main (int argc, char** argv){

   ros::init (argc, argv, "some_init");
   ros::NodeHandle nh;
   ros::Subscriber sub = nh.subscribe ("output", 100, cloud_cb);
   pub = nh.advertise<sensor_msgs::PointCloud2> ("output", 100);


   //Publish the first message so we can trigger cloud_cb for the first time
   float x=0,y=0,z=0;
   pcl::PointCloud<pcl::PointXYZ>::Ptr msg (new pcl::PointCloud<pcl::PointXYZ>);
   msg->header.frame_id = "some_frame";
   msg->height = msg->width = 1;
   msg->points.push_back (pcl::PointXYZ(x, y, z));
   pub.publish (msg);

   ros::spin ();

}
edit flag offensive delete link more

Comments

1

Small side note: you don't need to put ros::spin inside a loop. It won't return until the node is shut down anyway.

Lorenz gravatar image Lorenz  ( 2012-10-12 04:32:11 -0500 )edit

@Lorenz totally true! I overlooked that detail, thanks for the note. I will change ros::spin for ros::spinOnce to keep consistency on the answer.

Martin Peris gravatar image Martin Peris  ( 2012-10-12 05:07:28 -0500 )edit
1

I believe that using ros::spin is a much better solution than calling ros::spinOnce() once a second. The reason is that with spinOnce, subscriber callbacks are only executed when you call that method, i.e. once a second you'll get all subscribers executed, then nothing happens for one second, ...

Lorenz gravatar image Lorenz  ( 2012-10-12 05:09:59 -0500 )edit

Well, depending on what you are trying to accomplish that can be argued, but this discussion would not be really relevant to the question at hand, so I will just modify my answer again :)

Martin Peris gravatar image Martin Peris  ( 2012-10-12 05:20:47 -0500 )edit

True, there are some cases when spinOnce is well-suited, mainly to prevent multi-threading issues. The main problem is to chose an appropriate spin rate.

Lorenz gravatar image Lorenz  ( 2012-10-12 05:26:47 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2012-10-11 05:07:15 -0500

Seen: 813 times

Last updated: Oct 12 '12