| 
					
	
	 
		Hi,
 
				I'm trying to implement two Orbecc Astra PRO cameras with RTAB-Map in ROS. I followed the example of demo_two_kinects.launch but when the nodelets are launched, the message says: waitForService: Service [/camera1/camera1_nodelet_manager/load_nodelet] has not been advertised, waiting.. waitForService: Service [/camera2/camera2_nodelet_manager/load_nodelet] has not been advertised, waiting... Launch file for RTAB <launch> <group ns="camera1"> <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="load depth_image_proc/rgbd_sync camera1_nodelet_manager" output="screen"> <remap from="rgb/image" to="/camera_1_rgb/image_raw"/> <remap from="depth/image" to="/camera_1/depth_registered/image_raw"/> <remap from="rgb/camera_info" to="/camera_1_rgb/camera_info"/> </node> </group> <group ns="camera2"> <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="load depth_image_proc/rgbd_sync camera2_nodelet_manager" output="screen"> <remap from="rgb/image" to="/camera_2_rgb/image_raw"/> <remap from="depth/image" to="/camera_2/depth_registered/image_raw"/> <remap from="rgb/camera_info" to="/camera_2_rgb/camera_info"/> </node> </group> <node pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen"> <remap from="rgbd_image0" to="/camera1/depth_registered/points"/> <remap from="rgbd_image1" to="/camera2/depth_registered/points"/> <remap from="odom" to="odom_vo"/> </node> </launch> The Orbeccs are launched from a different file. Could someone point me to the right direction? Much appreciated, Bas  | 
			
| 
					
	 Administrator 
	
	
	
				 | 
				
					
	
	 
		Hi,
 
				a quick fix would be to use standalone nodelets: instead of "load depth_image_proc/rgbd_sync camera1_nodelet_manager", set "standalone depth_image_proc/rgbd_sync" This is because freenect.launch or openni.launch uses a camera nodelet manager. You may look for the astra launch if there is also a nodelet manager, if so use it instead of "standalone" to avoid serialization/deserialization of the image messages. cheers, Mathieu  | 
			
| 
					
	
	 
		Hi matlabbe,
 
				Thank you for the reply. I tried the standalone nodelets but results in pages long errors. The atra package is very similar to the openni package but i just dont know where i can find the name of the nodelet manager. This is what i found: <arg name="manager" value="$(arg camera)_nodelet_manager" /> <arg name="debug" default="false" /> <include file="$(find rgbd_launch)/launch/includes/manager.launch.xml"> <arg name="name" value="$(arg manager)" /> <arg name="debug" value="$(arg debug)" /> <arg name="num_worker_threads" value="$(arg num_worker_threads)" /> </include> but giving the "$(arg camera)_nodelet_manager" still results in the same waitforservice.  | 
			
| 
					
	
	 
		I figured out the nodelet name, was all about the _ .
 
				But now i get an error that suggests that the nodelet does not exist. Failed to load nodelet [/camera_1/rgbd_sync] of type [depth_image_proc/rgbd_sync] even after refreshing the cache: According to the loaded plugin descriptions the class depth_image_proc/rgbd_sync with base class type nodelet::Nodelet does not exist. I tried another random nodelet and gave the same result. Would you know if this is an environment configureation issue?  | 
			
| 
					
	 Administrator 
	
	
	
				 | 
				
					
	
	 
		Is the setup.bash sourced? http://wiki.ros.org/kinetic/Installation/Ubuntu#kinetic.2BAC8-Installation.2BAC8-DebEnvironment.Environment_setup 
				If I install ros-kinetic-astra-launch and launch astra.launch, it seems that there is no nodelet problem: 
$ sudo apt-get install ros-kinetic-astra-launch
$ roslaunch astra_launch astra.launch
... logging to /home/mathieu/.ros/log/eb24631a-5aa6-11e8-8135-c42c030ca39d/roslaunch-mathieu-Aspire-MC605-20389.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://mathieu-Aspire-MC605:40466/
SUMMARY
========
PARAMETERS
 * /camera/camera_nodelet_manager/num_worker_threads: 4
 * /camera/depth_rectify_depth/interpolation: 0
 * /camera/driver/auto_exposure: True
 * /camera/driver/auto_white_balance: True
 * /camera/driver/bootorder: 0
 * /camera/driver/color_depth_synchronization: False
 * /camera/driver/depth_camera_info_url: 
 * /camera/driver/depth_frame_id: camera_depth_opti...
 * /camera/driver/depth_registration: False
 * /camera/driver/device_id: #1
 * /camera/driver/devnums: 1
 * /camera/driver/rgb_camera_info_url: 
 * /camera/driver/rgb_frame_id: camera_rgb_optica...
 * /rosdistro: kinetic
 * /rosversion: 1.12.13
NODES
  /camera/
    camera_nodelet_manager (nodelet/nodelet)
    depth_metric (nodelet/nodelet)
    depth_metric_rect (nodelet/nodelet)
    depth_points (nodelet/nodelet)
    depth_rectify_depth (nodelet/nodelet)
    depth_registered_sw_metric_rect (nodelet/nodelet)
    driver (nodelet/nodelet)
    points_xyzrgb_sw_registered (nodelet/nodelet)
    register_depth_rgb (nodelet/nodelet)
    rgb_rectify_color (nodelet/nodelet)
  /
    camera_base_link (tf/static_transform_publisher)
    camera_base_link1 (tf/static_transform_publisher)
    camera_base_link2 (tf/static_transform_publisher)
    camera_base_link3 (tf/static_transform_publisher)
auto-starting new master
process[master]: started with pid [20399]
ROS_MASTER_URI=http://localhost:11311
setting /run_id to eb24631a-5aa6-11e8-8135-c42c030ca39d
process[rosout-1]: started with pid [20412]
started core service [/rosout]
process[camera/camera_nodelet_manager-2]: started with pid [20424]
process[camera/driver-3]: started with pid [20430]
process[camera/rgb_rectify_color-4]: started with pid [20431]
process[camera/depth_rectify_depth-5]: started with pid [20432]
process[camera/depth_metric_rect-6]: started with pid [20442]
process[camera/depth_metric-7]: started with pid [20456]
process[camera/depth_points-8]: started with pid [20470]
process[camera/register_depth_rgb-9]: started with pid [20484]
process[camera/points_xyzrgb_sw_registered-10]: started with pid [20486]
process[camera/depth_registered_sw_metric_rect-11]: started with pid [20503]
process[camera_base_link-12]: started with pid [20545]
process[camera_base_link1-13]: started with pid [20559]
process[camera_base_link2-14]: started with pid [20562]
process[camera_base_link3-15]: started with pid [20580]
[ INFO] [1526653361.285933059]: Initializing nodelet with 4 worker threads.
[ INFO] [1526653361.471240851]: No matching device found.... waiting for devices. Reason: std::__cxx11::string astra_wrapper::AstraDriver::resolveDeviceURI(const string&) @ /tmp/binarydeb/ros-kinetic-astra-camera-0.2.2/src/astra_driver.cpp @ 741 : Invalid device number 1, there are 0 devices connected.
[ INFO] [1526653364.471490445]: No matching device found.... waiting for devices. Reason: std::__cxx11::string astra_wrapper::AstraDriver::resolveDeviceURI(const string&) @ /tmp/binarydeb/ros-kinetic-astra-camera-0.2.2/src/astra_driver.cpp @ 741 : Invalid device number 1, there are 0 devices connected.
Well I don't have an astra camera, so I cannot see if images are actually published. The nodelet manager "camera_nodelet_manager" is in "camera" namespace. So to add a nodelet to it, we should load it with "camera/camera_nodelet_manager".
cheers, Mathieu  | 
			
| 
					
	
	 
		Thank you for taking a look.
 
				I managed to get the nodelets. The only thing left is to figure out how to get the point cloud to be published as i get this message: [ WARN] [1527083804.674772661]: /rgbd_odometry: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. /rgbd_odometry subscribed to (approx sync): /camera1/cloud, /camera2/cloud All the topics which the nodelets sub to are being published.  | 
			
| 
					
	 Administrator 
	
	
	
				 | 
				
					
	
	 
		Hi,
 
				rgbd_odometry subscribes to images, not point clouds. Can you show the launch file? cheers, Mathieu  | 
			
| 
					
	
	 
		It works!
 
				Thx for helping out. Launch file for the next person: <launch> <group ns="camera_1"> <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="load rtabmap_ros/rgbd_sync camera_1_nodelet_manager" output="screen"> <remap from="rgb/image" to="rgb/image_raw"/> <remap from="depth/image" to="depth_registered/image_raw"/> <remap from="rgb/camera_info" to="rgb/camera_info"/> </node> </group> <group ns="camera_2"> <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="load rtabmap_ros/rgbd_sync camera_2_nodelet_manager" output="screen"> <remap from="rgb/image" to="rgb/image_raw"/> <remap from="depth/image" to="depth_registered/image_raw"/> <remap from="rgb/camera_info" to="rgb/camera_info"/> </node> </group> <node pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen"> <remap from="rgbd_image0" to="/camera_1/rgbd_image"/> <remap from="rgbd_image1" to="/camera_2/rgbd_image"/> <remap from="odom" to="odom_vo"/> </node> </launch>  | 
			
| Free forum by Nabble | Edit this page | 
	
	
		