Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "ros/ros.h"
00029 #include <rtabmap/utilite/ULogger.h>
00030 #include <rtabmap/utilite/UDirectory.h>
00031 #include <rtabmap/core/CameraStereo.h>
00032 #include <rtabmap/core/util2d.h>
00033 #include <rtabmap_ros/MsgConversion.h>
00034 #include <image_transport/image_transport.h>
00035 #include <sensor_msgs/CameraInfo.h>
00036 #include <cv_bridge/cv_bridge.h>
00037
00038 int main(int argc, char** argv)
00039 {
00040 ULogger::setType(ULogger::kTypeConsole);
00041 ULogger::setLevel(ULogger::kInfo);
00042
00043 ros::init(argc, argv, "uvc_stereo_camera");
00044
00045 ros::NodeHandle pnh("~");
00046 double rate = 0.0;
00047 std::string id = "camera";
00048 std::string frameId = "camera_link";
00049 double scale = 1.0;
00050 pnh.param("rate", rate, rate);
00051 pnh.param("camera_id", id, id);
00052 pnh.param("frame_id", frameId, frameId);
00053 pnh.param("scale", scale, scale);
00054
00055 rtabmap::CameraStereoVideo camera(0, false, rate);
00056
00057 if(camera.init(UDirectory::homeDir() + "/.ros/camera_info", id))
00058 {
00059 ros::NodeHandle nh;
00060 ros::NodeHandle left_nh(nh, "left");
00061 ros::NodeHandle right_nh(nh, "right");
00062 image_transport::ImageTransport left_it(left_nh);
00063 image_transport::ImageTransport right_it(right_nh);
00064
00065 image_transport::Publisher imageLeftPub = left_it.advertise(left_nh.resolveName("image_raw"), 1);
00066 image_transport::Publisher imageRightPub = right_it.advertise(right_nh.resolveName("image_raw"), 1);
00067 ros::Publisher infoLeftPub = left_nh.advertise<sensor_msgs::CameraInfo>(left_nh.resolveName("camera_info"), 1);
00068 ros::Publisher infoRightPub = right_nh.advertise<sensor_msgs::CameraInfo>(right_nh.resolveName("camera_info"), 1);
00069
00070 while(ros::ok())
00071 {
00072 rtabmap::SensorData data = camera.takeImage();
00073
00074 ros::Time currentTime = ros::Time::now();
00075
00076 cv_bridge::CvImage imageLeft;
00077 imageLeft.header.frame_id = frameId;
00078 imageLeft.header.stamp = currentTime;
00079 imageLeft.encoding = "bgr8";
00080 cv::resize(data.imageRaw(), imageLeft.image, cv::Size(0,0), scale, scale, CV_INTER_AREA);
00081 imageLeftPub.publish(imageLeft.toImageMsg());
00082
00083 cv_bridge::CvImage imageRight;
00084 imageRight.header = imageLeft.header;
00085 imageRight.encoding = "mono8";
00086 cv::resize(data.rightRaw(), imageRight.image, cv::Size(0,0), scale, scale, CV_INTER_AREA);
00087 imageRightPub.publish(imageRight.toImageMsg());
00088
00089 sensor_msgs::CameraInfo infoLeft, infoRight;
00090 rtabmap_ros::cameraModelToROS(data.stereoCameraModel().left().scaled(scale), infoLeft);
00091 rtabmap_ros::cameraModelToROS(data.stereoCameraModel().right().scaled(scale), infoRight);
00092 infoLeft.header = imageLeft.header;
00093 infoRight.header = imageLeft.header;
00094 infoLeftPub.publish(infoLeft);
00095 infoRightPub.publish(infoRight);
00096
00097 ros::spinOnce();
00098 }
00099 }
00100 else
00101 {
00102 ROS_ERROR("Could not initialize the camera!");
00103 }
00104
00105 return 0;
00106 }