00001 /* 00002 * Copyright (C) 2015-2016 Fetch Robotics Inc. 00003 * Copyright (C) 2013-2014 Unbounded Robotics Inc. 00004 * 00005 * Licensed under the Apache License, Version 2.0 (the "License"); 00006 * you may not use this file except in compliance with the License. 00007 * You may obtain a copy of the License at 00008 * 00009 * http://www.apache.org/licenses/LICENSE-2.0 00010 * 00011 * Unless required by applicable law or agreed to in writing, software 00012 * distributed under the License is distributed on an "AS IS" BASIS, 00013 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00014 * See the License for the specific language governing permissions and 00015 * limitations under the License. 00016 */ 00017 00018 // Author: Michael Ferguson 00019 00020 #ifndef ROBOT_CALIBRATION_CAPTURE_DEPTH_CAMERA_H 00021 #define ROBOT_CALIBRATION_CAPTURE_DEPTH_CAMERA_H 00022 00023 #include <ros/ros.h> 00024 #include <sensor_msgs/CameraInfo.h> 00025 #include <robot_calibration_msgs/CalibrationData.h> 00026 #include <robot_calibration_msgs/ExtendedCameraInfo.h> 00027 00028 namespace robot_calibration 00029 { 00030 00032 class DepthCameraInfoManager 00033 { 00034 public: 00035 DepthCameraInfoManager() : camera_info_valid_(false) {} 00036 virtual ~DepthCameraInfoManager() {} 00037 00038 bool init(ros::NodeHandle& n) 00039 { 00040 std::string topic_name; 00041 n.param<std::string>("camera_info_topic", topic_name, "/head_camera/depth/camera_info"); 00042 00043 camera_info_subscriber_ = n.subscribe(topic_name, 00044 1, 00045 &DepthCameraInfoManager::cameraInfoCallback, 00046 this); 00047 00048 // Get parameters of drivers 00049 if (!n.getParam("/head_camera/driver/z_offset_mm", z_offset_mm_) || 00050 !n.getParam("/head_camera/driver/z_scaling", z_scaling_)) 00051 { 00052 ROS_ERROR("/head_camera/driver is not set, are drivers running?"); 00053 z_offset_mm_ = 0; 00054 z_scaling_ = 1; 00055 } 00056 00057 // Wait for camera_info 00058 int count = 25; 00059 while (--count) 00060 { 00061 if (camera_info_valid_) 00062 { 00063 return true; 00064 } 00065 ros::Duration(0.1).sleep(); 00066 ros::spinOnce(); 00067 } 00068 00069 ROS_WARN("CameraInfo receive timed out."); 00070 return false; 00071 } 00072 00073 robot_calibration_msgs::ExtendedCameraInfo getDepthCameraInfo() 00074 { 00075 robot_calibration_msgs::ExtendedCameraInfo info; 00076 info.camera_info = *camera_info_ptr_; 00077 info.parameters.resize(2); 00078 info.parameters[0].name = "z_offset_mm"; 00079 info.parameters[0].value = z_offset_mm_; 00080 info.parameters[1].name = "z_scaling"; 00081 info.parameters[1].value = z_scaling_; 00082 return info; 00083 } 00084 00085 private: 00086 void cameraInfoCallback(const sensor_msgs::CameraInfo::Ptr camera_info) 00087 { 00088 camera_info_ptr_ = camera_info; 00089 camera_info_valid_ = true; 00090 } 00091 00092 ros::Subscriber camera_info_subscriber_; 00093 bool camera_info_valid_; 00094 00095 sensor_msgs::CameraInfo::Ptr camera_info_ptr_; 00096 00097 double z_offset_mm_; 00098 double z_scaling_; 00099 }; 00100 00101 } // namespace robot_calibration 00102 00103 #endif // ROBOT_CALIBRATION_CAPTURE_DEPTH_CAMERA_H