ROS Learning Series--Roomba, Xtion Pro live 360-degree panorama photo Panorama unable to start the solution

Source: Internet
Author: User

Turtlebot has an application panorama to realize iPhone360 panorama photography function. The official use of the Create base and Kinnect, when using the Roomba base and the Xtion Pro live package, found that the tutorial does not start.


1. Start

Roslaunch turtlebot_bringup minimal.launch       \ Load wheel drive <pre>roslaunch Turtlebot_panorama panorama.launch     \ \ Start Panorama

Open another Shell window

Rosservice Call Turtlebot_panorama/take_pano 0 360.0 30.0 0.3   ordered a camera spin

This time found that Roomba-driven Turtlebot no response at all, the next step to analyze the problem.


2. Problem analysis

Open source code panorama.cpp, see a large number of log ("...") Output Debugging information:

//*************//logging//*************void panoapp::log (std::string log) {std_msgs:  : String msg;  Msg.data = log;  Pub_log.publish (msg); Ros_info_stream (log);} Panoapp::P Anoapp (): NH (), PRIV_NH ("~") {  std::string name = Ros::this_node::getname ();  Ros::p Aram::p Aram <int> ("~default_mode", Default_mode, 1);  Ros::p Aram::p aram<double> ("~default_pano_angle", Default_pano_angle, (2 * m_pi));  Ros::p Aram::p aram<double> ("~default_snap_interval", DEFAULT_SNAP_ Interval, 2.0);  Ros::p Aram::p aram<double> ("~default_rotation_velocity", default_rotation_velocity, 0.3 );  Ros::p Aram::p aram<std::string> ("~camera_name", params["Camera_name"], "/camera/rgb");  Ros:: Param::p aram<std::string> ("~bag_location", params["Bag_location"], "/home/turtlebot/pano.bag");  pub_ Log = priv_nh.advertise<std_msgs::string> ("log", +);} 
From here we can see that all the information has been sent to turtlebot\log this topic inside, then monitor some of this topic:

Rostopic  

Execute the start command again:

Rosservice Call Turtlebot_panorama/take_pano 0 360.0 30.0 0.3   ordered a camera spin

At this time, you can see the Turtlebot\log output log:

[Well time xxxxx]: Starting panorama Creation.[well time xxxxx]: Pano ROS action goal sent.<pre name= "code" class= "CPP" >[well time xxxxx]: Pano action goal just went active.
<pre name= "code" class= "CPP" >[well time xxxxx]: Snap

Obviously, it's stuck on snap snaps, so let's take a look at this piece of code:

void Panoapp::snap () {log ("snap"); Pub_action_snap.publish (empty_msg);} void Panoapp::init () {  ...................... //*************************** //Pano_ros API //   Pano_ros_client = new Actionlib::simpleactionclient<pano_ros:: Panocaptureaction> ("Pano_server", True);  log ("Waiting for Pano ROS server ...");  pano_ros_client-> Waitforserver (); 'll wait for infinite time  log ("Connected to Pano ROS server.");   PUB_ACTION_SNAP = nh.advertise<std_msgs::empty> ("Pano_server/snap", +);  pub_action_stop = Nh.advertise<std_msgs::empty> ("Pano_server/stop", +);  image_transport::imagetransport It_pano (NH);   sub_stitched = It_pano.subscribe ("Pano_server/stitch", 1, &PANOAPP::STITCHEDIMAGECB, this);  ..............................}
The function of the capture graph is placed in another process. The implementation of "Pano_server/snap" is in turtlebot_apps/software/pano/pano_ros/nodes/capture_server.py:

 def pano_capture (self, goal): If Self._capture_job was not none:raise Exception ("Cannot run Multile cap Ture jobs. Todo:pre-eempt existing Job ") Rospy.loginfo ('%s:pano Capture Goal: \n\tcamera [%s] '% (self._action_name, G  oal.camera_topic)) pano_id = Int (Rospy.get_time ()) #TODO make this a parameter,        Bag, publisher, etc ...                        Capturer = Self._capture_interface () #= bagcapture (pano_id,goal.bag_filename or None) Capturer.start (pano_id,goal)  self._snap_requested = False #reset capture_job = Self._capture_job = Panocapturejob (pano_id, Capturer) Camera_topic = Goal.camera_topic or Rospy.resolve_name (' camera ') #TODO: FIX ONCE openni API is F Ixed image_topic = Rospy.names.ns_join (camera_topic, ' image_color ') Camera_info_topic = Rospy.names.ns_join ( Camera_topic, ' Camera_info ') rospy.loginfo ('%s:starting capture of pano_id%d.\n\timage [%s]\n\tCamera info[%s] '% (Self._action_name, pano_id, Image_topic, camera_info_topic)) grabber = Ima Gegrabber (Image_topic, Camera_info_topic, SELF.CAPTURE_FN) # local VARs Server = Self._server preempt ed = False Rospy.loginfo ('%s:executing capture of pano_id%d '% (Self._action_name, pano_id)) # t  His would become true while Capture_job.result was None and not preempted and not Rospy.is_shutdown (): If Server.is_preempt_requested (): Rospy.loginfo ('%s:preempted '% self._action_name) server.se T_preempted () capture_job.cancel () preempted = True ELSE:ROSPY.SL                Eep (0.001) #let the node rest a bit result = Capture_job.result Grabber.stop () If Result:rospy.loginfo ('%s:succeeded, [%s] Images.\nresult:%s '% (Self._action_name, Result.n_captures, R Esult)) Server.set_succeeded (Result) Self._capture_job = None 

16th, 17 line display while listening to wait "Image_color" "camera_info" two topic, they are OPenNI2 published image data, see Imagegrabber code Discovery, inside is in sync wait two Topic trigger the camera operation (message_filters) when there is data at the same time. Timesynchronizer ())


This time we look at these two themes for images and information:

$ rosrun image_view image_view image:=/camera/rgb/image_color$ rostopic echo/camera/rgb/camera_info

It can be seen that there is no image in the Image_view, so it can be judged that the subject of the image is caused by inconsistency between Kinnect and Xtionpro.


The real image theme is here:

$ rosrun Image_view Image_view Image:=/camera/rgb/image_raw
You can see that there are images in the Image_view.


Conclusion

Xtion Pro Live image data is published in/camera/rgb/image_raw, but turtlebot_apps/software/pano/pano_ros/nodes/capture_server.py The inside has been listening to the/camera/rgb/image_color theme, causing no images to appear.


Solution Solutions

Remap topic Map Theme, modify Turtlebot_panorama/launch/panorama.launch. As below, add remap to line 15th, map Two themes, point the program to/camera/rgb/image_raw

<launch> <!--3d sensor; We just need RGB images--<include file= "$ (find Turtlebot_bringup)/launch/3dsensor.launch" > <arg name= "R    Gb_processing "value=" true "/> <arg name=" ir_processing "value=" false "/> <arg name= "depth_processing" value= "false"/> <arg name= "depth_registered_processing" value=            "False"/> <arg name= "Depth_registration" value= "false"/> <arg name= "disparity_processing" Value= "false"/> <arg name= "disparity_registered_processing" value= "false"/> <arg name= "scan_pr Ocessing "value=" false "/> </include> <node name=" Pano_server "pkg=" Pano_ros "type=" capture_s erver.py "output=" screen "> <remap from=" camera/rgb/image_color "to=" Camera/rgb/image_raw "/> </node> & Lt;node name= "Turtlebot_panorama" pkg= "Turtlebot_panorama" type= "Panorama" output= "screen" > <param name= "Default_mode" value= "1"/> <param name= "Default_pano_angle" value= "6.28318530718"/> <!--2 * Pi--    <param name= "Default_snap_interval" value= "2.0"/> <param name= "default_rotation_velocity" value= "0.3"/> <param name= "Camera_name" value= "Camera/rgb"/> <param name= "bag_location" value= "/tmp/turtlebot_  Panorama.bag "/> <remap from=" Cmd_vel "to="/cmd_vel_mux/input/navi "/> <remap from=" Odom "to="/odom "/> </node></launch>


Copyright NOTICE: This article for Bo Master original article, without Bo Master permission not reproduced.

ROS Learning Series--Roomba, Xtion Pro live 360-degree panorama photo Panorama unable to start the solution

Contact Us

The content source of this page is from Internet, which doesn't represent Alibaba Cloud's opinion; products and services mentioned on that page don't have any relationship with Alibaba Cloud. If the content of the page makes you feel confusing, please write us an email, we will handle the problem within 5 days after receiving your email.

If you find any instances of plagiarism from the community, please send an email to: info-contact@alibabacloud.com and provide relevant evidence. A staff member will contact you within 5 working days.

A Free Trial That Lets You Build Big!

Start building with 50+ products and up to 12 months usage for Elastic Compute Service

  • Sales Support

    1 on 1 presale consultation

  • After-Sales Support

    24/7 Technical Support 6 Free Tickets per Quarter Faster Response

  • Alibaba Cloud offers highly flexible support services tailored to meet your exact needs.