StereoCameraNode.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include "ros/ros.h"
32 #include <rtabmap/core/util2d.h>
35 #include <sensor_msgs/CameraInfo.h>
36 #include <cv_bridge/cv_bridge.h>
37 
38 int main(int argc, char** argv)
39 {
42 
43  ros::init(argc, argv, "uvc_stereo_camera");
44 
45  ros::NodeHandle pnh("~");
46  double rate = 0.0;
47  std::string id = "camera";
48  std::string frameId = "camera_link";
49  double scale = 1.0;
50  pnh.param("rate", rate, rate);
51  pnh.param("camera_id", id, id);
52  pnh.param("frame_id", frameId, frameId);
53  pnh.param("scale", scale, scale);
54 
55  rtabmap::CameraStereoVideo camera(0, false, rate);
56 
57  if(camera.init(UDirectory::homeDir() + "/.ros/camera_info", id))
58  {
59  ros::NodeHandle nh;
60  ros::NodeHandle left_nh(nh, "left");
61  ros::NodeHandle right_nh(nh, "right");
62  image_transport::ImageTransport left_it(left_nh);
63  image_transport::ImageTransport right_it(right_nh);
64 
65  image_transport::Publisher imageLeftPub = left_it.advertise(left_nh.resolveName("image_raw"), 1);
66  image_transport::Publisher imageRightPub = right_it.advertise(right_nh.resolveName("image_raw"), 1);
67  ros::Publisher infoLeftPub = left_nh.advertise<sensor_msgs::CameraInfo>(left_nh.resolveName("camera_info"), 1);
68  ros::Publisher infoRightPub = right_nh.advertise<sensor_msgs::CameraInfo>(right_nh.resolveName("camera_info"), 1);
69 
70  while(ros::ok())
71  {
73 
74  ros::Time currentTime = ros::Time::now();
75 
76  cv_bridge::CvImage imageLeft;
77  imageLeft.header.frame_id = frameId;
78  imageLeft.header.stamp = currentTime;
79  imageLeft.encoding = "bgr8";
80  cv::resize(data.imageRaw(), imageLeft.image, cv::Size(0,0), scale, scale, CV_INTER_AREA);
81  imageLeftPub.publish(imageLeft.toImageMsg());
82 
83  cv_bridge::CvImage imageRight;
84  imageRight.header = imageLeft.header;
85  imageRight.encoding = "mono8";
86  cv::resize(data.rightRaw(), imageRight.image, cv::Size(0,0), scale, scale, CV_INTER_AREA);
87  imageRightPub.publish(imageRight.toImageMsg());
88 
89  if(data.stereoCameraModels().size())
90  {
91  sensor_msgs::CameraInfo infoLeft, infoRight;
92  rtabmap_ros::cameraModelToROS(data.stereoCameraModels()[0].left().scaled(scale), infoLeft);
93  rtabmap_ros::cameraModelToROS(data.stereoCameraModels()[0].right().scaled(scale), infoRight);
94  infoLeft.header = imageLeft.header;
95  infoRight.header = imageLeft.header;
96  infoLeftPub.publish(infoLeft);
97  infoRightPub.publish(infoRight);
98  }
99  else
100  {
101  ROS_ERROR("No calibration loaded!");
102  }
103 
104  ros::spinOnce();
105  }
106  }
107  else
108  {
109  ROS_ERROR("Could not initialize the camera!");
110  }
111 
112  return 0;
113 }
static std::string homeDir()
data
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string encoding
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
const std::vector< StereoCameraModel > & stereoCameraModels() const
static void setLevel(ULogger::Level level)
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
cv::Mat rightRaw() const
SensorData takeImage(CameraInfo *info=0)
sensor_msgs::ImagePtr toImageMsg() const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
CameraWrapper * camera
Definition: CameraNode.cpp:258
const cv::Mat & imageRaw() const
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
ROSCPP_DECL bool ok()
std::string resolveName(const std::string &name, bool remap=true) const
void cameraModelToROS(const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publish(const sensor_msgs::Image &message) const
string frameId
Definition: patrol.py:11
int main(int argc, char **argv)
static Time now()
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
std_msgs::Header header


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40