$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00036 00037 #include "camera_offsetter/generic_offsetter.h" 00038 #include "sensor_msgs/Image.h" 00039 #include "sensor_msgs/CameraInfo.h" 00040 00041 using namespace std; 00042 00043 namespace camera_offsetter 00044 { 00045 00046 class MonoOffsetter : public GenericOffsetter 00047 { 00048 public: 00049 MonoOffsetter() 00050 { 00051 ros::NodeHandle nh_private("~"); 00052 00053 cam_name_ = nh_.resolveName("camera"); 00054 if (cam_name_ == "camera") 00055 ROS_WARN("camera was not remapped. Are you sure your camera namespace is 'camera'?"); 00056 00057 source_nh_ = ros::NodeHandle(cam_name_); 00058 offset_nh_ = ros::NodeHandle(cam_name_ + "_offset"); 00059 00060 vector<string> image_topics; 00061 00062 bool offset_raw = false; 00063 nh_private.getParam("use_raw", offset_raw); 00064 if (offset_raw) 00065 image_topics.push_back("image_raw"); 00066 00067 bool offset_rect = false; 00068 nh_private.getParam("use_rect", offset_rect); 00069 if (offset_rect) 00070 image_topics.push_back("image_rect"); 00071 00072 bool offset_rect_color = false; 00073 nh_private.getParam("use_rect_color", offset_rect_color); 00074 if (offset_rect_color) 00075 image_topics.push_back("image_rect_color"); 00076 00077 for (size_t i=0; i < image_topics.size(); i++) 00078 { 00079 ros::Publisher pub = offset_nh_.advertise<sensor_msgs::Image>(image_topics[i], 1); 00080 00081 ros::SubscribeOptions ops; 00082 00083 boost::function< void(const sensor_msgs::ImageConstPtr&) > f = boost::bind(&MonoOffsetter::imageCb, this, _1, pub); 00084 ros::Subscriber sub = source_nh_.subscribe(image_topics[i], 1, f); 00085 image_subs_.push_back(sub); 00086 image_pubs_.push_back(pub); 00087 } 00088 00089 info_sub_ = source_nh_.subscribe("camera_info", 1, &MonoOffsetter::infoCb, this); 00090 info_pub_ = offset_nh_.advertise<sensor_msgs::CameraInfo>("camera_info", 1); 00091 } 00092 00093 void imageCb(const sensor_msgs::ImageConstPtr& msg, ros::Publisher image_pub) 00094 { 00095 sensor_msgs::Image next_image = *msg; 00096 next_image.header.frame_id = msg->header.frame_id + frame_suffix_; 00097 image_pub.publish(next_image); 00098 00099 publishTransform(msg->header.stamp, next_image.header.frame_id, msg->header.frame_id); 00100 } 00101 00102 void infoCb(const sensor_msgs::CameraInfoConstPtr& msg) 00103 { 00104 sensor_msgs::CameraInfo next_info = *msg; 00105 next_info.header.frame_id = msg->header.frame_id + frame_suffix_; 00106 info_pub_.publish(next_info); 00107 } 00108 00109 private: 00110 ros::NodeHandle nh_; 00111 ros::NodeHandle source_nh_; 00112 ros::NodeHandle offset_nh_; 00113 00114 string cam_name_; 00115 00116 vector<ros::Subscriber> image_subs_; 00117 vector<ros::Publisher> image_pubs_; 00118 00119 ros::Subscriber info_sub_; 00120 ros::Publisher info_pub_; 00121 } ; 00122 00123 } 00124 00125 using namespace camera_offsetter; 00126 00127 int main(int argc, char** argv) 00128 { 00129 ros::init(argc, argv, "mono_offsetter"); 00130 00131 MonoOffsetter offsetter; 00132 00133 ros::spin(); 00134 }