Robotics StackExchange | Archived questions

pr2 camera subscriber

Hello everyone!

First I am using the groovy version of ROS under ubuntu 12.04.

I have some issues with the ImageTransporter Subscriber. I am trying to save pictures from different points of the environment using a pr2 robot.

I use a lookAt function described here to point to a coordinate in the environment and then subscribe to the "widestereo/left/imagemono" topic.

Here is the code I use for saving the picture:

void savePicture(const sensor_msgs::ImageConstPtr& msg){
  std::stringstream s;
  s<<"image"<<numImage<<".png";
  try
    {
      cv::imwrite(s.str().c_str(), cv_bridge::toCvShare(msg, "bgr8")->image);
    }
  catch(std::runtime_error& ex)
    {
      fprintf(stderr, "Exception converting image to PNG format: %s\n", ex.what());
    }
}

And here is my "main" function:

int main(int argc, char** argv)
{
  //init the ROS node
  ros::init(argc, argv, "image_listener");
  ros::NodeHandle nh;

  RobotHead head(nh);
  image_transport::ImageTransport it(nh);

  float angle = -M_PI;

  numImage = 0; //Global variable to increment each time a picture is taken
  while(angle<M_PI)
    {
      head.lookAt("base_link",cos(angle),sin(angle),1.2);
      image_transport::Subscriber sub = it.subscribe("wide_stereo/left/image_mono", 1, savePicture);
      numImage++;
      angle = angle + (M_PI/4.0);
    }
  ros::spin();
}

The thing is that this code is correctly compiled but doesn't save any image. When I put the ros::spin() in the while loop it only saves the first point given to the lookAt() function so it seems that the saving works.

Any help or advice is welcome and thank you for reading.

Asked by Nassim A. on 2015-01-06 09:59:48 UTC

Comments

Answers

Subscribers take a nonzero amount of time to become ready, and only need to be called once, so your call to image_transport::Subscriber sub = it.subscribe(...) needs to happen outside the while loop.

Asked by Dan Lazewatsky on 2015-01-06 11:17:01 UTC

Comments

Thank you very much for your answer! When I did that it only saved the last picture. I thought it was due to an overwriting problem with savePicture() function. And when I put the numImage++ in the savePicture() function it worked but saved the whole panorama and I only need some points of it.

Asked by Nassim A. on 2015-01-06 12:01:42 UTC

@Nassim A.: please don't use answers for posting comments. Use comments for that :).

Asked by gvdhoorn on 2015-01-06 12:37:33 UTC

I have finally found out! I only had to chage the ros::spin() to a ros::spinOnce() and put it in the while loop with the subscriber outside the while loop. Thank you very much for your help.

Asked by Nassim A. on 2015-01-14 05:59:22 UTC

Comments