|
From: <pmi...@us...> - 2009-07-31 22:17:25
|
Revision: 20324
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20324&view=rev
Author: pmihelich
Date: 2009-07-31 22:17:14 +0000 (Fri, 31 Jul 2009)
Log Message:
-----------
Renamed CamInfo message to CameraInfo.
Modified Paths:
--------------
pkg/trunk/calibration/kinematic_calibration/deprecated/camera_cal_sampler.h
pkg/trunk/calibration/kinematic_calibration/msg/CalibrationData2.msg
pkg/trunk/calibration/kinematic_calibration/msg/SensorKinematics.msg
pkg/trunk/calibration/kinematic_calibration/src/laser_head_grabber.cpp
pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp
pkg/trunk/drivers/cam/forearm_cam/src/nodes/forearm_node.cpp
pkg/trunk/drivers/cam/forearm_cam/src/nodes/forearm_node_new.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_prosilica.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_stereo_camera.h
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_prosilica.cpp
pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_stereo_camera.cpp
pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/projection.h
pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_pcd_via_service.cpp
pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map.cpp
pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map_via_service.cpp
pkg/trunk/mapping/annotated_planar_patch_map/src/image_value_node.cpp
pkg/trunk/mapping/annotated_planar_patch_map/src/projection.cpp
pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp
pkg/trunk/openrave_planning/openraveros/src/rosserver.h
pkg/trunk/openrave_planning/openraveros/srv/robot_sensorgetdata.srv
pkg/trunk/sandbox/camera_calibration/include/camera_calibration/pinhole.h
pkg/trunk/sandbox/camera_calibration/src/library/pinhole.cpp
pkg/trunk/sandbox/mturk_grab_object/include/mturk_grab_object/grasp_table_object_node.h
pkg/trunk/sandbox/planar_objects/src/box_detector.cpp
pkg/trunk/sandbox/planar_objects/src/box_detector.h
pkg/trunk/sandbox/planar_objects/src/cornercandidate.h
pkg/trunk/sandbox/rf_detector/include/ObjectInPerspective.h
pkg/trunk/sandbox/rf_detector/src/ObjectInPerspective.cpp
pkg/trunk/sandbox/rf_detector/src/RFDetector.cpp
pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/srv/PolledImage.srv
pkg/trunk/stacks/common_msgs/sensor_msgs/msg/RawStereo.msg
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector_vision.cpp
pkg/trunk/stacks/stereo/stereo_image_proc/include/cam_bridge.h
pkg/trunk/stacks/stereo/stereo_image_proc/src/imageproc.cpp
pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp
pkg/trunk/stacks/visual_feature_detectors/checkerboard_detector/checkerboard_detector.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/include/outlet_detection/tracker_base.h
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting2.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/tracker_base.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/camera_display.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/camera_display.h
pkg/trunk/vision/led_detection/include/led_detection/led_detector.h
pkg/trunk/vision/led_detection/include/led_detection/led_detector_node.h
pkg/trunk/vision/led_detection/src/led_detector.cpp
pkg/trunk/vision/people/src/face_detection.cpp
pkg/trunk/vision/people/src/pedestrian_detector_HOG.cpp
pkg/trunk/vision/people/src/stereo_color_tracker.cpp
pkg/trunk/vision/people/src/stereo_face_color_tracker.cpp
pkg/trunk/vision/people/src/track_starter_gui.cpp
pkg/trunk/vision/recognition_lambertian/src/publish_scene.cpp
pkg/trunk/vision/recognition_lambertian/src/rec_lam_normal_features.cpp
pkg/trunk/vision/recognition_lambertian/src/recognition_lambertian.cpp
pkg/trunk/vision/stereo_capture/src/periodic_capture.cpp
pkg/trunk/vision/stereo_capture/src/stereo_capture.cpp
pkg/trunk/vision/stereo_checkerboard_detector/include/stereo_checkerboard_detector/reprojection_helper.h
pkg/trunk/vision/stereo_checkerboard_detector/include/stereo_checkerboard_detector/stereo_checkerboard_helper.h
pkg/trunk/vision/stereo_checkerboard_detector/src/image_pc_debugger.cpp
pkg/trunk/vision/stereo_checkerboard_detector/src/reprojection_helper.cpp
pkg/trunk/vision/stereo_checkerboard_detector/src/stereo_checkerboard_helper.cpp
pkg/trunk/vision/stereo_checkerboard_detector/src/stereo_checkerboard_node.cpp
Added Paths:
-----------
pkg/trunk/stacks/camera_drivers/prosilica_cam/srv/CameraInfo.srv
pkg/trunk/stacks/common_msgs/sensor_msgs/msg/CameraInfo.msg
Removed Paths:
-------------
pkg/trunk/stacks/camera_drivers/prosilica_cam/srv/CamInfo.srv
pkg/trunk/stacks/common_msgs/sensor_msgs/msg/CamInfo.msg
Modified: pkg/trunk/calibration/kinematic_calibration/deprecated/camera_cal_sampler.h
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/deprecated/camera_cal_sampler.h 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/calibration/kinematic_calibration/deprecated/camera_cal_sampler.h 2009-07-31 22:17:14 UTC (rev 20324)
@@ -46,7 +46,7 @@
#include "kinematic_calibration/Capture.h"
#include "robot_msgs/MechanismState.h"
#include "sensor_msgs/Image.h"
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
#include "topic_synchronizer/topic_synchronizer.h"
#include "tinyxml/tinyxml.h"
Modified: pkg/trunk/calibration/kinematic_calibration/msg/CalibrationData2.msg
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/msg/CalibrationData2.msg 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/calibration/kinematic_calibration/msg/CalibrationData2.msg 2009-07-31 22:17:14 UTC (rev 20324)
@@ -18,4 +18,4 @@
# Data from multiple monocular cameras
sensor_msgs/Image[] image
-sensor_msgs/CamInfo[] cam_info
+sensor_msgs/CameraInfo[] cam_info
Modified: pkg/trunk/calibration/kinematic_calibration/msg/SensorKinematics.msg
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/msg/SensorKinematics.msg 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/calibration/kinematic_calibration/msg/SensorKinematics.msg 2009-07-31 22:17:14 UTC (rev 20324)
@@ -9,8 +9,8 @@
sensor_msgs/Image right_image
sensor_msgs/Image disparity_image
sensor_msgs/StereoInfo stereo_info
-sensor_msgs/CamInfo left_info
-sensor_msgs/CamInfo right_info
+sensor_msgs/CameraInfo left_info
+sensor_msgs/CameraInfo right_info
# Mechanism State - Stores the robots joint angles
mechanism_msgs/MechanismState mechanism_state
Modified: pkg/trunk/calibration/kinematic_calibration/src/laser_head_grabber.cpp
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/src/laser_head_grabber.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/calibration/kinematic_calibration/src/laser_head_grabber.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -44,7 +44,7 @@
#include "robot_msgs/PointCloud.h"
#include "sensor_msgs/Image.h"
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
#include "kinematic_calibration/CalSnapshot.h"
@@ -90,8 +90,8 @@
ADD_MSG(robot_msgs::PointCloud, corners_right_) ;
ADD_MSG(sensor_msgs::Image, left_debug_) ;
ADD_MSG(sensor_msgs::Image, right_debug_) ;
- ADD_MSG(sensor_msgs::CamInfo, left_info_) ;
- ADD_MSG(sensor_msgs::CamInfo, right_info_) ;
+ ADD_MSG(sensor_msgs::CameraInfo, left_info_) ;
+ ADD_MSG(sensor_msgs::CameraInfo, right_info_) ;
// Laser Messages
boost::mutex laser_lock_ ;
@@ -333,8 +333,8 @@
SensorSample left_cb_sample = buildCamCornersSample(safe_corners_left_, "stereo_left", "6x8_cb") ;
SensorSample right_cb_sample = buildCamCornersSample(safe_corners_right_, "stereo_right", "6x8_cb") ;
- SensorSample left_info_sample = buildCamInfoSample(safe_left_info_, "stereo_left_info","6x8_cb") ;
- SensorSample right_info_sample = buildCamInfoSample(safe_right_info_, "stereo_right_info","6x8_cb") ;
+ SensorSample left_info_sample = buildCameraInfoSample(safe_left_info_, "stereo_left_info","6x8_cb") ;
+ SensorSample right_info_sample = buildCameraInfoSample(safe_right_info_, "stereo_right_info","6x8_cb") ;
snapshot_msg_.samples.resize(5) ;
snapshot_msg_.samples[0] = laser_sample ;
@@ -391,7 +391,7 @@
return sample ;
}
- SensorSample buildCamInfoSample(const sensor_msgs::CamInfo& info, const string& sensor, const string& target)
+ SensorSample buildCameraInfoSample(const sensor_msgs::CameraInfo& info, const string& sensor, const string& target)
{
SensorSample sample ;
sample.sensor = sensor ;
Modified: pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/calibration/kinematic_calibration/src/sensor_kinematics_grabber.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -46,7 +46,7 @@
#include "sensor_msgs/RawStereo.h"
#include "sensor_msgs/Image.h"
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
#include "kinematic_calibration/CalibrationData2.h"
@@ -94,8 +94,8 @@
// HiRes Camera messages
sensor_msgs::Image hi_res_image_ ;
sensor_msgs::Image safe_hi_res_image_ ;
- sensor_msgs::CamInfo hi_res_info_ ;
- sensor_msgs::CamInfo safe_hi_res_info_ ;
+ sensor_msgs::CameraInfo hi_res_info_ ;
+ sensor_msgs::CameraInfo safe_hi_res_info_ ;
boost::mutex hi_res_lock_ ;
// Point Cloud Messages
Modified: pkg/trunk/drivers/cam/forearm_cam/src/nodes/forearm_node.cpp
===================================================================
--- pkg/trunk/drivers/cam/forearm_cam/src/nodes/forearm_node.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/drivers/cam/forearm_cam/src/nodes/forearm_node.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -42,7 +42,7 @@
#include <ros/node.h>
#include <sensor_msgs/Image.h>
-#include <sensor_msgs/CamInfo.h>
+#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/FillImage.h>
#include <dynamic_reconfigure/SensorLevels.h>
#include <diagnostic_updater/diagnostic_updater.h>
@@ -192,9 +192,9 @@
// Publications
diagnostic_updater::DiagnosedPublisher<sensor_msgs::Image> cam_pub_;
- diagnostic_updater::DiagnosedPublisher<sensor_msgs::CamInfo> cam_info_pub_;
+ diagnostic_updater::DiagnosedPublisher<sensor_msgs::CameraInfo> cam_info_pub_;
sensor_msgs::Image image_;
- sensor_msgs::CamInfo cam_info_;
+ sensor_msgs::CameraInfo cam_info_;
// Services
@@ -633,7 +633,7 @@
// Receive frames through callback
if (calibrated_)
- cam_info_pub_.set_publisher(node_handle_.advertise<sensor_msgs::CamInfo>("~cam_info", 1));
+ cam_info_pub_.set_publisher(node_handle_.advertise<sensor_msgs::CameraInfo>("~cam_info", 1));
else
cam_info_pub_.set_publisher(ros::Publisher());
Modified: pkg/trunk/drivers/cam/forearm_cam/src/nodes/forearm_node_new.cpp
===================================================================
--- pkg/trunk/drivers/cam/forearm_cam/src/nodes/forearm_node_new.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/drivers/cam/forearm_cam/src/nodes/forearm_node_new.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -42,7 +42,7 @@
#include <ros/node.h>
#include <sensor_msgs/Image.h>
-#include <sensor_msgs/CamInfo.h>
+#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/FillImage.h>
#include <dynamic_reconfigure/SensorLevels.h>
#include <diagnostic_updater/diagnostic_updater.h>
@@ -192,9 +192,9 @@
// Publications
diagnostic_updater::DiagnosedPublisher<sensor_msgs::Image> cam_pub_;
- diagnostic_updater::DiagnosedPublisher<sensor_msgs::CamInfo> cam_info_pub_;
+ diagnostic_updater::DiagnosedPublisher<sensor_msgs::CameraInfo> cam_info_pub_;
sensor_msgs::Image image_;
- sensor_msgs::CamInfo cam_info_;
+ sensor_msgs::CameraInfo cam_info_;
// Services
@@ -633,7 +633,7 @@
// Receive frames through callback
if (calibrated_)
- cam_info_pub_.set_publisher(node_handle_.advertise<sensor_msgs::CamInfo>("~cam_info", 1));
+ cam_info_pub_.set_publisher(node_handle_.advertise<sensor_msgs::CameraInfo>("~cam_info", 1));
else
cam_info_pub_.set_publisher(ros::Publisher());
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_prosilica.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_prosilica.h 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_prosilica.h 2009-07-31 22:17:14 UTC (rev 20324)
@@ -35,11 +35,11 @@
// image components
#include "opencv_latest/CvBridge.h"
#include "sensor_msgs/Image.h"
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
// prosilica components
#include "prosilica/prosilica.h"
-#include "prosilica_cam/CamInfo.h"
+#include "prosilica_cam/CameraInfo.h"
#include "prosilica_cam/PolledImage.h"
@@ -128,8 +128,8 @@
private: static void mouse_cb(int event, int x, int y, int flags, void* param) { };
/// \brief Service call to publish images, cam info
- private: bool camInfoService(prosilica_cam::CamInfo::Request &req,
- prosilica_cam::CamInfo::Response &res);
+ private: bool camInfoService(prosilica_cam::CameraInfo::Request &req,
+ prosilica_cam::CameraInfo::Response &res);
private: bool triggeredGrab(prosilica_cam::PolledImage::Request &req,
prosilica_cam::PolledImage::Response &res);
@@ -146,8 +146,8 @@
private: sensor_msgs::Image imageMsg;
private: sensor_msgs::Image imageRectMsg;
private: sensor_msgs::Image *roiImageMsg;
- private: sensor_msgs::CamInfo *camInfoMsg;
- private: sensor_msgs::CamInfo *roiCamInfoMsg;
+ private: sensor_msgs::CameraInfo *camInfoMsg;
+ private: sensor_msgs::CameraInfo *roiCameraInfoMsg;
/// \brief Parameters
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_stereo_camera.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_stereo_camera.h 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/ros_stereo_camera.h 2009-07-31 22:17:14 UTC (rev 20324)
@@ -40,7 +40,7 @@
#include <sensor_msgs/Image.h>
#include "sensor_msgs/RawStereo.h"
#include "sensor_msgs/StereoInfo.h"
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
#include "sensor_msgs/DisparityInfo.h"
namespace gazebo
@@ -167,8 +167,8 @@
private: sensor_msgs::RawStereo rawStereoMsg;
private: sensor_msgs::Image* leftImageMsg;
private: sensor_msgs::Image* rightImageMsg;
- private: sensor_msgs::CamInfo* leftCamInfoMsg;
- private: sensor_msgs::CamInfo* rightCamInfoMsg;
+ private: sensor_msgs::CameraInfo* leftCameraInfoMsg;
+ private: sensor_msgs::CameraInfo* rightCameraInfoMsg;
private: sensor_msgs::StereoInfo* stereoInfoMsg;
/// \brief A mutex to lock access to fields that are used in message callbacks
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_prosilica.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_prosilica.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_prosilica.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -45,7 +45,7 @@
#include <sensor_msgs/Image.h>
-#include <sensor_msgs/CamInfo.h>
+#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/FillImage.h>
#include <diagnostic_updater/diagnostic_updater.h>
@@ -163,19 +163,19 @@
ROS_DEBUG("prosilica image topic name %s", this->imageTopicName.c_str());
this->image_pub_ = this->rosnode_->advertise<sensor_msgs::Image>(this->imageTopicName,1);
this->image_rect_pub_ = this->rosnode_->advertise<sensor_msgs::Image>(this->imageRectTopicName,1);
- this->cam_info_pub_ = this->rosnode_->advertise<sensor_msgs::CamInfo>(this->camInfoTopicName,1);
+ this->cam_info_pub_ = this->rosnode_->advertise<sensor_msgs::CameraInfo>(this->camInfoTopicName,1);
this->cam_info_ser_ = this->rosnode_->advertiseService(this->camInfoServiceName,&RosProsilica::camInfoService, this);
this->poll_ser_ = this->rosnode_->advertiseService(this->pollServiceName,&RosProsilica::triggeredGrab, this);
}
////////////////////////////////////////////////////////////////////////////////
// service call to return camera info
-bool RosProsilica::camInfoService(prosilica_cam::CamInfo::Request &req,
- prosilica_cam::CamInfo::Response &res)
+bool RosProsilica::camInfoService(prosilica_cam::CameraInfo::Request &req,
+ prosilica_cam::CameraInfo::Response &res)
{
// should return the cam info for the entire camera frame
this->camInfoMsg = &res.cam_info;
- // fill CamInfo
+ // fill CameraInfo
this->camInfoMsg->header.frame_id = this->frameName;
this->camInfoMsg->header.stamp = ros::Time((unsigned long)floor(Simulator::Instance()->GetSimTime()));
this->camInfoMsg->height = this->myParent->GetImageHeight();
@@ -247,51 +247,51 @@
{
this->lock.lock();
- // fill CamInfo
- this->roiCamInfoMsg = &res.cam_info;
- this->roiCamInfoMsg->header.frame_id = this->frameName;
- this->roiCamInfoMsg->header.stamp = ros::Time((unsigned long)floor(Simulator::Instance()->GetSimTime()));
- this->roiCamInfoMsg->width = req.width; //this->myParent->GetImageWidth() ;
- this->roiCamInfoMsg->height = req.height; //this->myParent->GetImageHeight();
+ // fill CameraInfo
+ this->roiCameraInfoMsg = &res.cam_info;
+ this->roiCameraInfoMsg->header.frame_id = this->frameName;
+ this->roiCameraInfoMsg->header.stamp = ros::Time((unsigned long)floor(Simulator::Instance()->GetSimTime()));
+ this->roiCameraInfoMsg->width = req.width; //this->myParent->GetImageWidth() ;
+ this->roiCameraInfoMsg->height = req.height; //this->myParent->GetImageHeight();
// distortion
- this->roiCamInfoMsg->D[0] = 0.0;
- this->roiCamInfoMsg->D[1] = 0.0;
- this->roiCamInfoMsg->D[2] = 0.0;
- this->roiCamInfoMsg->D[3] = 0.0;
- this->roiCamInfoMsg->D[4] = 0.0;
+ this->roiCameraInfoMsg->D[0] = 0.0;
+ this->roiCameraInfoMsg->D[1] = 0.0;
+ this->roiCameraInfoMsg->D[2] = 0.0;
+ this->roiCameraInfoMsg->D[3] = 0.0;
+ this->roiCameraInfoMsg->D[4] = 0.0;
// original camera matrix
- this->roiCamInfoMsg->K[0] = this->focal_length;
- this->roiCamInfoMsg->K[1] = 0.0;
- this->roiCamInfoMsg->K[2] = this->Cx - req.region_x;
- this->roiCamInfoMsg->K[3] = 0.0;
- this->roiCamInfoMsg->K[4] = this->focal_length;
- this->roiCamInfoMsg->K[5] = this->Cy - req.region_y;
- this->roiCamInfoMsg->K[6] = 0.0;
- this->roiCamInfoMsg->K[7] = 0.0;
- this->roiCamInfoMsg->K[8] = 1.0;
+ this->roiCameraInfoMsg->K[0] = this->focal_length;
+ this->roiCameraInfoMsg->K[1] = 0.0;
+ this->roiCameraInfoMsg->K[2] = this->Cx - req.region_x;
+ this->roiCameraInfoMsg->K[3] = 0.0;
+ this->roiCameraInfoMsg->K[4] = this->focal_length;
+ this->roiCameraInfoMsg->K[5] = this->Cy - req.region_y;
+ this->roiCameraInfoMsg->K[6] = 0.0;
+ this->roiCameraInfoMsg->K[7] = 0.0;
+ this->roiCameraInfoMsg->K[8] = 1.0;
// rectification
- this->roiCamInfoMsg->R[0] = 1.0;
- this->roiCamInfoMsg->R[1] = 0.0;
- this->roiCamInfoMsg->R[2] = 0.0;
- this->roiCamInfoMsg->R[3] = 0.0;
- this->roiCamInfoMsg->R[4] = 1.0;
- this->roiCamInfoMsg->R[5] = 0.0;
- this->roiCamInfoMsg->R[6] = 0.0;
- this->roiCamInfoMsg->R[7] = 0.0;
- this->roiCamInfoMsg->R[8] = 1.0;
+ this->roiCameraInfoMsg->R[0] = 1.0;
+ this->roiCameraInfoMsg->R[1] = 0.0;
+ this->roiCameraInfoMsg->R[2] = 0.0;
+ this->roiCameraInfoMsg->R[3] = 0.0;
+ this->roiCameraInfoMsg->R[4] = 1.0;
+ this->roiCameraInfoMsg->R[5] = 0.0;
+ this->roiCameraInfoMsg->R[6] = 0.0;
+ this->roiCameraInfoMsg->R[7] = 0.0;
+ this->roiCameraInfoMsg->R[8] = 1.0;
// camera projection matrix (same as camera matrix due to lack of distortion/rectification) (is this generated?)
- this->roiCamInfoMsg->P[0] = this->focal_length;
- this->roiCamInfoMsg->P[1] = 0.0;
- this->roiCamInfoMsg->P[2] = this->Cx - req.region_x;
- this->roiCamInfoMsg->P[3] = 0.0;
- this->roiCamInfoMsg->P[4] = 0.0;
- this->roiCamInfoMsg->P[5] = this->focal_length;
- this->roiCamInfoMsg->P[6] = this->Cy - req.region_y;
- this->roiCamInfoMsg->P[7] = 0.0;
- this->roiCamInfoMsg->P[8] = 0.0;
- this->roiCamInfoMsg->P[9] = 0.0;
- this->roiCamInfoMsg->P[10] = 1.0;
- this->roiCamInfoMsg->P[11] = 0.0;
+ this->roiCameraInfoMsg->P[0] = this->focal_length;
+ this->roiCameraInfoMsg->P[1] = 0.0;
+ this->roiCameraInfoMsg->P[2] = this->Cx - req.region_x;
+ this->roiCameraInfoMsg->P[3] = 0.0;
+ this->roiCameraInfoMsg->P[4] = 0.0;
+ this->roiCameraInfoMsg->P[5] = this->focal_length;
+ this->roiCameraInfoMsg->P[6] = this->Cy - req.region_y;
+ this->roiCameraInfoMsg->P[7] = 0.0;
+ this->roiCameraInfoMsg->P[8] = 0.0;
+ this->roiCameraInfoMsg->P[9] = 0.0;
+ this->roiCameraInfoMsg->P[10] = 1.0;
+ this->roiCameraInfoMsg->P[11] = 0.0;
// copy data into image
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_stereo_camera.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_stereo_camera.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/ros_stereo_camera.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -82,8 +82,8 @@
// RawStereo.msg
this->leftImageMsg = &(this->rawStereoMsg.left_image);
this->rightImageMsg = &(this->rawStereoMsg.right_image);
- this->leftCamInfoMsg = &(this->rawStereoMsg.left_info);
- this->rightCamInfoMsg = &(this->rawStereoMsg.right_info);
+ this->leftCameraInfoMsg = &(this->rawStereoMsg.left_info);
+ this->rightCameraInfoMsg = &(this->rawStereoMsg.right_info);
this->stereoInfoMsg = &(this->rawStereoMsg.stereo_info);
ROS_DEBUG("stereo: done with constuctor");
@@ -323,93 +323,93 @@
this->stereoInfoMsg->RP[14] = -1.0/this->baseline;
this->stereoInfoMsg->RP[15] = (this->Cx-this->CxPrime)/this->baseline;
- // fill CamInfo left_info
- this->leftCamInfoMsg->header = this->rawStereoMsg.header;
- this->leftCamInfoMsg->height = this->leftCamera->GetImageHeight();
- this->leftCamInfoMsg->width = this->leftCamera->GetImageWidth() ;
+ // fill CameraInfo left_info
+ this->leftCameraInfoMsg->header = this->rawStereoMsg.header;
+ this->leftCameraInfoMsg->height = this->leftCamera->GetImageHeight();
+ this->leftCameraInfoMsg->width = this->leftCamera->GetImageWidth() ;
// distortion
- this->leftCamInfoMsg->D[0] = 0.0;
- this->leftCamInfoMsg->D[1] = 0.0;
- this->leftCamInfoMsg->D[2] = 0.0;
- this->leftCamInfoMsg->D[3] = 0.0;
- this->leftCamInfoMsg->D[4] = 0.0;
+ this->leftCameraInfoMsg->D[0] = 0.0;
+ this->leftCameraInfoMsg->D[1] = 0.0;
+ this->leftCameraInfoMsg->D[2] = 0.0;
+ this->leftCameraInfoMsg->D[3] = 0.0;
+ this->leftCameraInfoMsg->D[4] = 0.0;
// original camera matrix
- this->leftCamInfoMsg->K[0] = this->focal_length;
- this->leftCamInfoMsg->K[1] = 0.0;
- this->leftCamInfoMsg->K[2] = this->Cx;
- this->leftCamInfoMsg->K[3] = 0.0;
- this->leftCamInfoMsg->K[4] = this->focal_length;
- this->leftCamInfoMsg->K[5] = this->Cy;
- this->leftCamInfoMsg->K[6] = 0.0;
- this->leftCamInfoMsg->K[7] = 0.0;
- this->leftCamInfoMsg->K[8] = 1.0;
+ this->leftCameraInfoMsg->K[0] = this->focal_length;
+ this->leftCameraInfoMsg->K[1] = 0.0;
+ this->leftCameraInfoMsg->K[2] = this->Cx;
+ this->leftCameraInfoMsg->K[3] = 0.0;
+ this->leftCameraInfoMsg->K[4] = this->focal_length;
+ this->leftCameraInfoMsg->K[5] = this->Cy;
+ this->leftCameraInfoMsg->K[6] = 0.0;
+ this->leftCameraInfoMsg->K[7] = 0.0;
+ this->leftCameraInfoMsg->K[8] = 1.0;
// rectification
- this->leftCamInfoMsg->R[0] = 1.0;
- this->leftCamInfoMsg->R[1] = 0.0;
- this->leftCamInfoMsg->R[2] = 0.0;
- this->leftCamInfoMsg->R[3] = 0.0;
- this->leftCamInfoMsg->R[4] = 1.0;
- this->leftCamInfoMsg->R[5] = 0.0;
- this->leftCamInfoMsg->R[6] = 0.0;
- this->leftCamInfoMsg->R[7] = 0.0;
- this->leftCamInfoMsg->R[8] = 1.0;
+ this->leftCameraInfoMsg->R[0] = 1.0;
+ this->leftCameraInfoMsg->R[1] = 0.0;
+ this->leftCameraInfoMsg->R[2] = 0.0;
+ this->leftCameraInfoMsg->R[3] = 0.0;
+ this->leftCameraInfoMsg->R[4] = 1.0;
+ this->leftCameraInfoMsg->R[5] = 0.0;
+ this->leftCameraInfoMsg->R[6] = 0.0;
+ this->leftCameraInfoMsg->R[7] = 0.0;
+ this->leftCameraInfoMsg->R[8] = 1.0;
// camera projection matrix (same as camera matrix due to lack of distortion/rectification) (is this generated?)
- this->leftCamInfoMsg->P[0] = this->focal_length;
- this->leftCamInfoMsg->P[1] = 0.0;
- this->leftCamInfoMsg->P[2] = this->Cx;
- this->leftCamInfoMsg->P[3] = 0.0;
- this->leftCamInfoMsg->P[4] = 0.0;
- this->leftCamInfoMsg->P[5] = this->focal_length;
- this->leftCamInfoMsg->P[6] = this->Cy;
- this->leftCamInfoMsg->P[7] = 0.0;
- this->leftCamInfoMsg->P[8] = 0.0;
- this->leftCamInfoMsg->P[9] = 0.0;
- this->leftCamInfoMsg->P[10] = 1.0;
- this->leftCamInfoMsg->P[11] = 0.0;
+ this->leftCameraInfoMsg->P[0] = this->focal_length;
+ this->leftCameraInfoMsg->P[1] = 0.0;
+ this->leftCameraInfoMsg->P[2] = this->Cx;
+ this->leftCameraInfoMsg->P[3] = 0.0;
+ this->leftCameraInfoMsg->P[4] = 0.0;
+ this->leftCameraInfoMsg->P[5] = this->focal_length;
+ this->leftCameraInfoMsg->P[6] = this->Cy;
+ this->leftCameraInfoMsg->P[7] = 0.0;
+ this->leftCameraInfoMsg->P[8] = 0.0;
+ this->leftCameraInfoMsg->P[9] = 0.0;
+ this->leftCameraInfoMsg->P[10] = 1.0;
+ this->leftCameraInfoMsg->P[11] = 0.0;
- // fill CamInfo right_info
- this->rightCamInfoMsg->header = this->rawStereoMsg.header;
- this->rightCamInfoMsg->height = this->rightCamera->GetImageHeight();
- this->rightCamInfoMsg->width = this->rightCamera->GetImageWidth() ;
+ // fill CameraInfo right_info
+ this->rightCameraInfoMsg->header = this->rawStereoMsg.header;
+ this->rightCameraInfoMsg->height = this->rightCamera->GetImageHeight();
+ this->rightCameraInfoMsg->width = this->rightCamera->GetImageWidth() ;
// distortion
- this->rightCamInfoMsg->D[0] = 0.0;
- this->rightCamInfoMsg->D[1] = 0.0;
- this->rightCamInfoMsg->D[2] = 0.0;
- this->rightCamInfoMsg->D[3] = 0.0;
- this->rightCamInfoMsg->D[4] = 0.0;
+ this->rightCameraInfoMsg->D[0] = 0.0;
+ this->rightCameraInfoMsg->D[1] = 0.0;
+ this->rightCameraInfoMsg->D[2] = 0.0;
+ this->rightCameraInfoMsg->D[3] = 0.0;
+ this->rightCameraInfoMsg->D[4] = 0.0;
// original camera matrix
- this->rightCamInfoMsg->K[0] = this->focal_length;
- this->rightCamInfoMsg->K[1] = 0.0;
- this->rightCamInfoMsg->K[2] = this->Cx;
- this->rightCamInfoMsg->K[3] = 0.0;
- this->rightCamInfoMsg->K[4] = this->focal_length;
- this->rightCamInfoMsg->K[5] = this->Cy;
- this->rightCamInfoMsg->K[6] = 0.0;
- this->rightCamInfoMsg->K[7] = 0.0;
- this->rightCamInfoMsg->K[8] = 1.0;
+ this->rightCameraInfoMsg->K[0] = this->focal_length;
+ this->rightCameraInfoMsg->K[1] = 0.0;
+ this->rightCameraInfoMsg->K[2] = this->Cx;
+ this->rightCameraInfoMsg->K[3] = 0.0;
+ this->rightCameraInfoMsg->K[4] = this->focal_length;
+ this->rightCameraInfoMsg->K[5] = this->Cy;
+ this->rightCameraInfoMsg->K[6] = 0.0;
+ this->rightCameraInfoMsg->K[7] = 0.0;
+ this->rightCameraInfoMsg->K[8] = 1.0;
// rectification
- this->rightCamInfoMsg->R[0] = 1.0;
- this->rightCamInfoMsg->R[1] = 0.0;
- this->rightCamInfoMsg->R[2] = 0.0;
- this->rightCamInfoMsg->R[3] = 0.0;
- this->rightCamInfoMsg->R[4] = 1.0;
- this->rightCamInfoMsg->R[5] = 0.0;
- this->rightCamInfoMsg->R[6] = 0.0;
- this->rightCamInfoMsg->R[7] = 0.0;
- this->rightCamInfoMsg->R[8] = 1.0;
+ this->rightCameraInfoMsg->R[0] = 1.0;
+ this->rightCameraInfoMsg->R[1] = 0.0;
+ this->rightCameraInfoMsg->R[2] = 0.0;
+ this->rightCameraInfoMsg->R[3] = 0.0;
+ this->rightCameraInfoMsg->R[4] = 1.0;
+ this->rightCameraInfoMsg->R[5] = 0.0;
+ this->rightCameraInfoMsg->R[6] = 0.0;
+ this->rightCameraInfoMsg->R[7] = 0.0;
+ this->rightCameraInfoMsg->R[8] = 1.0;
// camera projection matrix (same as camera matrix due to lack of distortion/rectification) (is this generated?)
- this->rightCamInfoMsg->P[0] = this->focal_length;
- this->rightCamInfoMsg->P[1] = 0.0;
- this->rightCamInfoMsg->P[2] = this->Cx;
- this->rightCamInfoMsg->P[3] = -this->focal_length*this->baseline;
- this->rightCamInfoMsg->P[4] = 0.0;
- this->rightCamInfoMsg->P[5] = this->focal_length;
- this->rightCamInfoMsg->P[6] = this->Cy;
- this->rightCamInfoMsg->P[7] = 0.0;
- this->rightCamInfoMsg->P[8] = 0.0;
- this->rightCamInfoMsg->P[9] = 0.0;
- this->rightCamInfoMsg->P[10] = 1.0;
- this->rightCamInfoMsg->P[11] = 0.0;
+ this->rightCameraInfoMsg->P[0] = this->focal_length;
+ this->rightCameraInfoMsg->P[1] = 0.0;
+ this->rightCameraInfoMsg->P[2] = this->Cx;
+ this->rightCameraInfoMsg->P[3] = -this->focal_length*this->baseline;
+ this->rightCameraInfoMsg->P[4] = 0.0;
+ this->rightCameraInfoMsg->P[5] = this->focal_length;
+ this->rightCameraInfoMsg->P[6] = this->Cy;
+ this->rightCameraInfoMsg->P[7] = 0.0;
+ this->rightCameraInfoMsg->P[8] = 0.0;
+ this->rightCameraInfoMsg->P[9] = 0.0;
+ this->rightCameraInfoMsg->P[10] = 1.0;
+ this->rightCameraInfoMsg->P[11] = 0.0;
// fill uint8 left_type
this->rawStereoMsg.left_type = this->rawStereoMsg.IMAGE_RAW;
Modified: pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/projection.h
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/projection.h 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/projection.h 2009-07-31 22:17:14 UTC (rev 20324)
@@ -51,7 +51,7 @@
#include <mapping_msgs/PolygonalMap.h>
#include <sensor_msgs/StereoInfo.h>
-#include <sensor_msgs/CamInfo.h>
+#include <sensor_msgs/CameraInfo.h>
#include <annotated_map_msgs/TaggedPolygonalMap.h>
#include <annotated_map_msgs/TaggedPolygon3D.h>
@@ -62,14 +62,14 @@
namespace projection
{
-void projectAnyObject(const sensor_msgs::CamInfo& cam_info,robot_msgs::Polygon3D polyIn,robot_msgs::Polygon3D& polyOut);
+void projectAnyObject(const sensor_msgs::CameraInfo& cam_info,robot_msgs::Polygon3D polyIn,robot_msgs::Polygon3D& polyOut);
void projectAnyObject(const sensor_msgs::StereoInfo& stereo_info_, const annotated_map_msgs::TaggedPolygonalMap& transformed_map_3D, annotated_map_msgs::TaggedPolygonalMap &transformed_map_2D);
-void projectAnyObject(const sensor_msgs::CamInfo& cam_info_, const annotated_map_msgs::TaggedPolygonalMap& transformed_map_3D, annotated_map_msgs::TaggedPolygonalMap &transformed_map_2D);
+void projectAnyObject(const sensor_msgs::CameraInfo& cam_info_, const annotated_map_msgs::TaggedPolygonalMap& transformed_map_3D, annotated_map_msgs::TaggedPolygonalMap &transformed_map_2D);
-void projectAnyObject(const sensor_msgs::CamInfo& cam_info_, const robot_msgs::PointCloud& source_3D, robot_msgs::PointCloud& target_2D);
+void projectAnyObject(const sensor_msgs::CameraInfo& cam_info_, const robot_msgs::PointCloud& source_3D, robot_msgs::PointCloud& target_2D);
@@ -82,7 +82,7 @@
-void projectAnyObjectNOP(const sensor_msgs::CamInfo& stereo_info_, const annotated_map_msgs::TaggedPolygonalMap& transformed_map_3D, annotated_map_msgs::TaggedPolygonalMap &transformed_map_2D);
+void projectAnyObjectNOP(const sensor_msgs::CameraInfo& stereo_info_, const annotated_map_msgs::TaggedPolygonalMap& transformed_map_3D, annotated_map_msgs::TaggedPolygonalMap &transformed_map_2D);
/* !
* \brief Finds which polygons are visible in the current view. The polygons should be transformed
Modified: pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_pcd_via_service.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_pcd_via_service.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_pcd_via_service.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -54,7 +54,7 @@
#include <mapping_msgs/PolygonalMap.h>
#include <sensor_msgs/StereoInfo.h>
-#include <sensor_msgs/CamInfo.h>
+#include <sensor_msgs/CameraInfo.h>
#include <std_msgs/ColorRGBA.h>
#include "tf/message_notifier.h"
@@ -154,7 +154,7 @@
annotation_notifier_->setTolerance(lifting_delay_+ros::Duration(0.1));
- typedef annotated_planar_patch_map::RollingHistory<sensor_msgs::CamInfo> cam_hist_type;
+ typedef annotated_planar_patch_map::RollingHistory<sensor_msgs::CameraInfo> cam_hist_type;
boost::shared_ptr<cam_hist_type> cam_hist_lookup(new cam_hist_type("cam_info","~cam_info_hist/"));
@@ -169,8 +169,8 @@
try{
ROS_INFO_STREAM("Annotation " << annotation->header.stamp);
- //const image_msgs::CamInfoConstPtr cam_info = cam_hist_->getMsgAtExactTime(annotation->header.stamp);
- const sensor_msgs::CamInfoConstPtr cam_info = cam_hist_->getMsgNearTime(annotation->header.stamp,ros::Duration(0.01));
+ //const image_msgs::CameraInfoConstPtr cam_info = cam_hist_->getMsgAtExactTime(annotation->header.stamp);
+ const sensor_msgs::CameraInfoConstPtr cam_info = cam_hist_->getMsgNearTime(annotation->header.stamp,ros::Duration(0.01));
if(cam_info==NULL)
{
@@ -195,7 +195,7 @@
}
void liftAndSend(const boost::shared_ptr<cv_mech_turk::ExternalAnnotation const> annotation,
- const boost::shared_ptr<sensor_msgs::CamInfo const> cam_info,
+ const boost::shared_ptr<sensor_msgs::CameraInfo const> cam_info,
const robot_msgs::PointCloud& cloud)
{
robot_msgs::PointCloud transformed_map_3D;
@@ -463,7 +463,7 @@
boost::shared_ptr<tf::TransformListener> tf_;
tf::MessageNotifier<cv_mech_turk::ExternalAnnotation>* annotation_notifier_ ;
- boost::shared_ptr<annotated_planar_patch_map::RollingHistory<sensor_msgs::CamInfo> > cam_hist_;
+ boost::shared_ptr<annotated_planar_patch_map::RollingHistory<sensor_msgs::CameraInfo> > cam_hist_;
boost::mutex lift_mutex_;
Modified: pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -54,7 +54,7 @@
#include <mapping_msgs/PolygonalMap.h>
#include <sensor_msgs/StereoInfo.h>
-#include <sensor_msgs/CamInfo.h>
+#include <sensor_msgs/CameraInfo.h>
#include <cv_mech_turk/ExternalAnnotation.h>
#include <annotated_map_msgs/TaggedPolygonalMap.h>
@@ -92,7 +92,7 @@
- caminfo_sub_ = n_.subscribe<sensor_msgs::CamInfo>( std::string("cam_info"), 100, boost::bind(&Annotation2DLifterToTaggedPatchMap::handleCamInfo, this,_1));
+ caminfo_sub_ = n_.subscribe<sensor_msgs::CameraInfo>( std::string("cam_info"), 100, boost::bind(&Annotation2DLifterToTaggedPatchMap::handleCameraInfo, this,_1));
annotation_sub_ = n_.subscribe<cv_mech_turk::ExternalAnnotation>( std::string("annotations_2d"), 100, boost::bind(&Annotation2DLifterToTaggedPatchMap::handleAnnotation, this,_1));
unlabeled_map_sub_ = n_.subscribe<annotated_map_msgs::TaggedPolygonalMap>( std::string("planar_map"), 100, boost::bind(&Annotation2DLifterToTaggedPatchMap::handleUnlabeledMap, this,_1));
@@ -112,7 +112,7 @@
unlabeled_map_=ptrMap;
printf("Unlabeled map\n");
}
- void handleCamInfo(const sensor_msgs::CamInfoConstPtr ptrInfo)
+ void handleCameraInfo(const sensor_msgs::CameraInfoConstPtr ptrInfo)
{
boost::mutex::scoped_lock lock(lift_mutex_);
cam_info_=ptrInfo;
@@ -396,7 +396,7 @@
cv_mech_turk::ExternalAnnotationConstPtr annotation2d_object_;
annotated_map_msgs::TaggedPolygonalMapConstPtr unlabeled_map_;
- sensor_msgs::CamInfoConstPtr cam_info_;
+ sensor_msgs::CameraInfoConstPtr cam_info_;
Modified: pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map_via_service.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map_via_service.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map_via_service.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -54,7 +54,7 @@
#include <mapping_msgs/PolygonalMap.h>
#include <sensor_msgs/StereoInfo.h>
-#include <sensor_msgs/CamInfo.h>
+#include <sensor_msgs/CameraInfo.h>
#include "tf/message_notifier.h"
#include <cv_mech_turk/ExternalAnnotation.h>
@@ -421,7 +421,7 @@
cv_mech_turk::ExternalAnnotation annotation2d_object_;
sensor_msgs::StereoInfo stereo_info_;
- //sensor_msgs::CamInfo stereo_info_;
+ //sensor_msgs::CameraInfo stereo_info_;
std::string fixed_frame_;
Modified: pkg/trunk/mapping/annotated_planar_patch_map/src/image_value_node.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/src/image_value_node.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/mapping/annotated_planar_patch_map/src/image_value_node.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -49,7 +49,7 @@
#include <mapping_msgs/PolygonalMap.h>
-#include <sensor_msgs/CamInfo.h>
+#include <sensor_msgs/CameraInfo.h>
#include <cv_mech_turk/ExternalAnnotation.h>
#include <annotated_map_msgs/TaggedPolygonalMap.h>
@@ -73,7 +73,7 @@
annotated_map_msgs::TaggedPolygonalMapConstPtr last_map_;
- sensor_msgs::CamInfoConstPtr cam_info_;
+ sensor_msgs::CameraInfoConstPtr cam_info_;
public:
@@ -87,7 +87,7 @@
tf_ = new tf::TransformListener( *node_handle_.getNode(), true);
subs_.push_back(node_handle_.subscribe<annotated_map_msgs::TaggedPolygonalMap>("annotated_map", 1000, &ImageValueNode::mapCallback, this));
- subs_.push_back(node_handle_.subscribe<sensor_msgs::CamInfo>("cam_info", 500, &ImageValueNode::caminfoCallback, this));
+ subs_.push_back(node_handle_.subscribe<sensor_msgs::CameraInfo>("cam_info", 500, &ImageValueNode::caminfoCallback, this));
//actual_topic_ = node_handle_.mapName("annotated_map");
}
@@ -99,7 +99,7 @@
last_map_=map;
}
- void caminfoCallback(const sensor_msgs::CamInfoConstPtr& si)
+ void caminfoCallback(const sensor_msgs::CameraInfoConstPtr& si)
{
cam_info_=si;
annotated_map_msgs::TaggedPolygonalMap transformed_map;
Modified: pkg/trunk/mapping/annotated_planar_patch_map/src/projection.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/src/projection.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/mapping/annotated_planar_patch_map/src/projection.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -79,7 +79,7 @@
}
}
-void annotated_planar_patch_map::projection::projectAnyObject(const sensor_msgs::CamInfo& cam_info,robot_msgs::Polygon3D polyIn,robot_msgs::Polygon3D& polyOut)
+void annotated_planar_patch_map::projection::projectAnyObject(const sensor_msgs::CameraInfo& cam_info,robot_msgs::Polygon3D polyIn,robot_msgs::Polygon3D& polyOut)
{
//Projection setup
CvMat *K_ = cvCreateMat(3, 3, CV_64FC1);
@@ -131,7 +131,7 @@
}
-void annotated_planar_patch_map::projection::projectAnyObject(const sensor_msgs::CamInfo& cam_info,const robot_msgs::PointCloud& source_3D,robot_msgs::PointCloud& target_2D)
+void annotated_planar_patch_map::projection::projectAnyObject(const sensor_msgs::CameraInfo& cam_info,const robot_msgs::PointCloud& source_3D,robot_msgs::PointCloud& target_2D)
{
//Projection setup
CvMat *K_ = cvCreateMat(3, 3, CV_64FC1);
@@ -327,7 +327,7 @@
-void annotated_planar_patch_map::projection::projectAnyObjectNOP(const sensor_msgs::CamInfo& stereo_info, const annotated_map_msgs::TaggedPolygonalMap& transformed_map_3D, annotated_map_msgs::TaggedPolygonalMap &transformed_map_2D)
+void annotated_planar_patch_map::projection::projectAnyObjectNOP(const sensor_msgs::CameraInfo& stereo_info, const annotated_map_msgs::TaggedPolygonalMap& transformed_map_3D, annotated_map_msgs::TaggedPolygonalMap &transformed_map_2D)
{
bool bSame = (&transformed_map_3D == &transformed_map_2D);
@@ -373,7 +373,7 @@
}
}
-void annotated_planar_patch_map::projection::projectAnyObject(const sensor_msgs::CamInfo& cam_info, const annotated_map_msgs::TaggedPolygonalMap& transformed_map_3D, annotated_map_msgs::TaggedPolygonalMap &transformed_map_2D)
+void annotated_planar_patch_map::projection::projectAnyObject(const sensor_msgs::CameraInfo& cam_info, const annotated_map_msgs::TaggedPolygonalMap& transformed_map_3D, annotated_map_msgs::TaggedPolygonalMap &transformed_map_2D)
{
bool bSame = (&transformed_map_3D == &transformed_map_2D);
Modified: pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp
===================================================================
--- pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -55,7 +55,7 @@
#include "opencv_latest/CvBridge.h"
#include "sensor_msgs/StereoInfo.h"
#include "sensor_msgs/DisparityInfo.h"
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
#include "sensor_msgs/Image.h"
#include "topic_synchronizer/topic_synchronizer.h"
@@ -110,7 +110,7 @@
sensor_msgs::Image dimage;
sensor_msgs::StereoInfo stinfo;
sensor_msgs::DisparityInfo dispinfo;
- sensor_msgs::CamInfo rcinfo;
+ sensor_msgs::CameraInfo rcinfo;
sensor_msgs::CvBridge lbridge;
sensor_msgs::CvBridge rbridge;
sensor_msgs::CvBridge dbridge;
Modified: pkg/trunk/openrave_planning/openraveros/src/rosserver.h
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/rosserver.h 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/openrave_planning/openraveros/src/rosserver.h 2009-07-31 22:17:14 UTC (rev 20324)
@@ -27,7 +27,7 @@
#include "openraveros.h"
#include "sensor_msgs/Image.h"
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
class ROSServer : public RaveServerBase
{
Modified: pkg/trunk/openrave_planning/openraveros/srv/robot_sensorgetdata.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/robot_sensorgetdata.srv 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/openrave_planning/openraveros/srv/robot_sensorgetdata.srv 2009-07-31 22:17:14 UTC (rev 20324)
@@ -19,5 +19,5 @@
float32[] laserint
## camera
-sensor_msgs/CamInfo caminfo # camera calibration parameters and where camera is
+sensor_msgs/CameraInfo caminfo # camera calibration parameters and where camera is
sensor_msgs/Image camimage # camera image
Modified: pkg/trunk/sandbox/camera_calibration/include/camera_calibration/pinhole.h
===================================================================
--- pkg/trunk/sandbox/camera_calibration/include/camera_calibration/pinhole.h 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/sandbox/camera_calibration/include/camera_calibration/pinhole.h 2009-07-31 22:17:14 UTC (rev 20324)
@@ -6,7 +6,7 @@
#include <string>
#include <opencv/cv.h>
#include <opencv/cvwimage.h>
-#include <sensor_msgs/CamInfo.h>
+#include <sensor_msgs/CameraInfo.h>
namespace camera_calibration {
@@ -27,9 +27,6 @@
// Can pass NULL for zero distortion
void setDistortion(const double* D);
- // Constructor/setter with params fx, fy, ...?
- // Setter from CamInfo message?
-
const std::string& name() const;
int width() const;
@@ -67,7 +64,7 @@
virtual bool save(const std::string& file_name) const;
virtual bool parse(const std::string& buffer, const std::string& format = "ini");
- virtual void fillCamInfo(sensor_msgs::CamInfo &info) const;
+ virtual void fillCameraInfo(sensor_msgs::CameraInfo &info) const;
protected:
std::string camera_name_;
Modified: pkg/trunk/sandbox/camera_calibration/src/library/pinhole.cpp
===================================================================
--- pkg/trunk/sandbox/camera_calibration/src/library/pinhole.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/sandbox/camera_calibration/src/library/pinhole.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -121,7 +121,7 @@
return success;
}
-void PinholeCameraModel::fillCamInfo(sensor_msgs::CamInfo &info) const
+void PinholeCameraModel::fillCameraInfo(sensor_msgs::CameraInfo &info) const
{
std::copy(K, K+9, &info.K[0]);
std::copy(D, D+5, &info.D[0]);
Modified: pkg/trunk/sandbox/mturk_grab_object/include/mturk_grab_object/grasp_table_object_node.h
===================================================================
--- pkg/trunk/sandbox/mturk_grab_object/include/mturk_grab_object/grasp_table_object_node.h 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/sandbox/mturk_grab_object/include/mturk_grab_object/grasp_table_object_node.h 2009-07-31 22:17:14 UTC (rev 20324)
@@ -41,7 +41,7 @@
// ROS messages
#include <robot_msgs/PointCloud.h>
#include <sensor_msgs/Image.h>
-#include <sensor_msgs/CamInfo.h>
+#include <sensor_msgs/CameraInfo.h>
#include <map>
@@ -61,7 +61,7 @@
{
public:
robot_msgs::PointCloudConstPtr cloud_;
- sensor_msgs::CamInfoConstPtr cam_info_;
+ sensor_msgs::CameraInfoConstPtr cam_info_;
sensor_msgs::ImageConstPtr image_;
tabletop_msgs::TableConstPtr table_;
Modified: pkg/trunk/sandbox/planar_objects/src/box_detector.cpp
===================================================================
--- pkg/trunk/sandbox/planar_objects/src/box_detector.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/sandbox/planar_objects/src/box_detector.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -114,12 +114,12 @@
dinfo_ = dinfo;
}
-void BoxDetector::linfoCallback(const sensor_msgs::CamInfo::ConstPtr& linfo)
+void BoxDetector::linfoCallback(const sensor_msgs::CameraInfo::ConstPtr& linfo)
{
linfo_ = linfo;
}
-void BoxDetector::rinfoCallback(const sensor_msgs::CamInfo::ConstPtr& rinfo)
+void BoxDetector::rinfoCallback(const sensor_msgs::CameraInfo::ConstPtr& rinfo)
{
rinfo_ = rinfo;
}
Modified: pkg/trunk/sandbox/planar_objects/src/box_detector.h
===================================================================
--- pkg/trunk/sandbox/planar_objects/src/box_detector.h 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/sandbox/planar_objects/src/box_detector.h 2009-07-31 22:17:14 UTC (rev 20324)
@@ -18,7 +18,7 @@
#include "sensor_msgs/Image.h"
#include "sensor_msgs/StereoInfo.h"
#include "sensor_msgs/DisparityInfo.h"
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
#include "opencv_latest/CvBridge.h"
#include "opencv/cxcore.h"
@@ -90,10 +90,10 @@
sensor_msgs::DisparityInfoConstPtr dinfo_;
ros::Subscriber linfo_sub_;
- sensor_msgs::CamInfoConstPtr linfo_;
+ sensor_msgs::CameraInfoConstPtr linfo_;
ros::Subscriber rinfo_sub_;
- sensor_msgs::CamInfoConstPtr rinfo_;
+ sensor_msgs::CameraInfoConstPtr rinfo_;
tf::TransformBroadcaster broadcaster_;
@@ -117,8 +117,8 @@
void dinfoCallback(const sensor_msgs::DisparityInfo::ConstPtr& disp_img);
void limageCallback(const sensor_msgs::Image::ConstPtr& left_img);
void rimageCallback(const sensor_msgs::Image::ConstPtr& right_img);
- void linfoCallback(const sensor_msgs::CamInfo::ConstPtr& rinfo);
- void rinfoCallback(const sensor_msgs::CamInfo::ConstPtr& linfo);
+ void linfoCallback(const sensor_msgs::CameraInfo::ConstPtr& rinfo);
+ void rinfoCallback(const sensor_msgs::CameraInfo::ConstPtr& linfo);
void syncCallback();
void buildRP();
Modified: pkg/trunk/sandbox/planar_objects/src/cornercandidate.h
===================================================================
--- pkg/trunk/sandbox/planar_objects/src/cornercandidate.h 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/sandbox/planar_objects/src/cornercandidate.h 2009-07-31 22:17:14 UTC (rev 20324)
@@ -18,7 +18,7 @@
#include "sensor_msgs/Image.h"
#include "sensor_msgs/StereoInfo.h"
#include "sensor_msgs/DisparityInfo.h"
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
#include "opencv_latest/CvBridge.h"
#include "opencv/cxcore.h"
Modified: pkg/trunk/sandbox/rf_detector/include/ObjectInPerspective.h
===================================================================
--- pkg/trunk/sandbox/rf_detector/include/ObjectInPerspective.h 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/sandbox/rf_detector/include/ObjectInPerspective.h 2009-07-31 22:17:14 UTC (rev 20324)
@@ -52,7 +52,7 @@
//#include <point_cloud_mapping/geometry/statistics.h>
#include <point_cloud_mapping/geometry/projections.h>
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
#include "robot_msgs/PointCloud.h"
#include "robot_msgs/Point32.h"
#include "robot_msgs/PointStamped.h"
@@ -77,7 +77,7 @@
float GetCameraHeight(const robot_msgs::PointCloud& pc, tf::TransformListener& tf_);
-float CalHorizontalLine( const robot_msgs::PointCloud& cloud, vector<double> plane_coeff, const sensor_msgs::CamInfo& lcinfo, tf::TransformListener& tf_);
+float CalHorizontalLine( const robot_msgs::PointCloud& cloud, vector<double> plane_coeff, const sensor_msgs::CameraInfo& lcinfo, tf::TransformListener& tf_);
void filterClusters(const robot_msgs::PointCloud& cloud, vector<robot_msgs::Point32>& centers, vector<robot_msgs::Point32>& clusters);
@@ -89,6 +89,6 @@
float findObjectPositionsFromStereo(const robot_msgs::PointCloud& cloud, vector<CvPoint>& locations, vector<CvPoint>& obj_bottom,
vector<float>& scales, vector<float>& scales_msun, tf::TransformListener& tf_, tf::TransformBroadcaster& broadcaster_,
- const sensor_msgs::CamInfo& lcinfo);
+ const sensor_msgs::CameraInfo& lcinfo);
-robot_msgs::Point project3DPointIntoImage(const sensor_msgs::CamInfo& cam_info, robot_msgs::PointStamped point, tf::TransformListener& tf_);
+robot_msgs::Point project3DPointIntoImage(const sensor_msgs::CameraInfo& cam_info, robot_msgs::PointStamped point, tf::TransformListener& tf_);
Modified: pkg/trunk/sandbox/rf_detector/src/ObjectInPerspective.cpp
===================================================================
--- pkg/trunk/sandbox/rf_detector/src/ObjectInPerspective.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/sandbox/rf_detector/src/ObjectInPerspective.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -220,7 +220,7 @@
return camera_center_table_frame.pts[0].z;
}
- float CalHorizontalLine( const PointCloud& cloud, vector<double> plane_coeff, const sensor_msgs::CamInfo& lcinfo, tf::TransformListener& tf_){
+ float CalHorizontalLine( const PointCloud& cloud, vector<double> plane_coeff, const sensor_msgs::CameraInfo& lcinfo, tf::TransformListener& tf_){
// calculate new plane_coeff which includes the origin pts
plane_coeff[3] = 0;
@@ -501,7 +501,7 @@
float findObjectPositionsFromStereo(const PointCloud& cloud, vector<CvPoint>& locations, vector<CvPoint>& obj_bottom,
vector<float>& scales, vector<float>& scales_msun, tf::TransformListener& tf_, tf::TransformBroadcaster& broadcaster_,
- const sensor_msgs::CamInfo& lcinfo)
+ const sensor_msgs::CameraInfo& lcinfo)
{
vector<double> plane;
PointCloud objects_pc;
@@ -576,7 +576,7 @@
return camera_height;
}
- Point project3DPointIntoImage(const sensor_msgs::CamInfo& cam_info, PointStamped point, tf::TransformListener& tf_)
+ Point project3DPointIntoImage(const sensor_msgs::CameraInfo& cam_info, PointStamped point, tf::TransformListener& tf_)
{
PointStamped image_point;
tf_.transformPoint(cam_info.header.frame_id, point, image_point);
Modified: pkg/trunk/sandbox/rf_detector/src/RFDetector.cpp
===================================================================
--- pkg/trunk/sandbox/rf_detector/src/RFDetector.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/sandbox/rf_detector/src/RFDetector.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -58,7 +58,7 @@
#include <point_cloud_mapping/sample_consensus/lmeds.h>
#include <point_cloud_mapping/geometry/projections.h>
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
#include "robot_msgs/PointCloud.h"
#include "robot_msgs/Point32.h"
#include "robot_msgs/PointStamped.h"
@@ -106,7 +106,7 @@
TopicSynchronizer sync_;
sensor_msgs::ImageConstPtr limage;
sensor_msgs::CvBridge lbridge;
- sensor_msgs::CamInfoConstPtr lcinfo_;
+ sensor_msgs::CameraInfoConstPtr lcinfo_;
ros::Subscriber left_image_sub_;
ros::Subscriber left_caminfo_image_sub_;
@@ -220,7 +220,7 @@
namedWindow("left_objbbx", 1);
// subscribe to topics
left_image_sub_ = n.subscribe("stereo/left/image_rect", 1, sync_.synchronize(&rf_detector::leftImageCallback, this));
- left_caminfo_image_sub_ = n.subscribe("stereo/left/cam_info", 1, sync_.synchronize(&rf_detector::leftCamInfoCallback, this));
+ left_caminfo_image_sub_ = n.subscribe("stereo/left/cam_info", 1, sync_.synchronize(&rf_detector::leftCameraInfoCallback, this));
cloud_sub_ = n.subscribe("stereo/cloud", 1, sync_.synchronize(&rf_detector::cloudCallback, this));
}
@@ -247,7 +247,7 @@
}
}
- void leftCamInfoCallback(const sensor_msgs::CamInfo::ConstPtr& info)
+ void leftCameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr& info)
{
lcinfo_ = info;
}
Modified: pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -39,7 +39,7 @@
#include "ros/node.h"
#include "sensor_msgs/Image.h"
#include "sensor_msgs/FillImage.h"
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
#include "sensor_msgs/StereoInfo.h"
#include "robot_msgs/PointCloud.h"
@@ -55,7 +55,7 @@
bool do_rectify_;
sensor_msgs::Image img_;
- sensor_msgs::CamInfo cam_info_;
+ sensor_msgs::CameraInfo cam_info_;
DiagnosticUpdater<DcamNode> diagnostic_;
diagnostic_updater::TimeStampStatus timestamp_diag_;
@@ -286,7 +286,7 @@
void advertiseImages(std::string base_name, cam::ImageData* img_data)
{
- advertise<sensor_msgs::CamInfo>(base_name + std::string("cam_info"), 1);
+ advertise<sensor_msgs::CameraInfo>(base_name + std::string("cam_info"), 1);
if (img_data->imRawType != COLOR_CODING_NONE)
advertise<sensor_msgs::Image>(base_name + std::string("image_raw"), 1);
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/fake_poll_node.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -1,9 +1,9 @@
#include "ros/node.h"
#include "sensor_msgs/Image.h"
-#include "sensor_msgs/CamInfo.h"
+#include "sensor_msgs/CameraInfo.h"
#include "sensor_msgs/FillImage.h"
#include "prosilica_cam/PolledImage.h"
-#include "prosilica_cam/CamInfo.h"
+#include "prosilica_cam/CameraInfo.h"
#include <cv.h>
#include <cvwimage.h>
@@ -60,8 +60,8 @@
cvReleaseMat(&D_);
}
- bool camInfo(prosilica_cam::CamInfo::Request &req,
- prosilica_cam::CamInfo::Response &rsp)
+ bool camInfo(prosilica_cam::CameraInfo::Request &req,
+ prosilica_cam::CameraInfo::Response &rsp)
{
memcpy((char*)(&rsp.cam_info.D[0]), (char*)(D_->data.db), 5*sizeof(double));
memcpy((char*)(&rsp.cam_info.K[0]), (char*)(K_->data.db), 9*sizeof(double));
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-07-31 22:10:05 UTC (rev 20323)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-07-31 22:17:14 UTC (rev 20324)
@@ -36,7 +36,7 @@
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
-#include <sensor_msgs/CamInfo.h>
+#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/FillImage.h>
#include <opencv_latest/CvBridge.h>
#include <camera_calibration/pinhole.h>
@@ -56,7 +56,7 @@
#include "prosilica/prosilica.h"
#include "prosilica/rolling_sum.h"
#include "prosilica_cam/PolledImage.h"
-#include "prosilica_cam/CamInfo.h"
+#include "prosilica_cam/CameraInfo.h"
class ProsilicaNode
{
@@ -76,7 +76,7 @@
// ROS messages
sensor_msgs::Image img_, rect_img_;
sensor_msgs::CvBridge img_bridge_, rect_img_bridge_;
- sensor_msgs::CamInfo cam_info_;
+ sensor_msgs::CameraInfo cam_info_;
sensor_msgs::Image thumbnail_;
int thumbnail_size_;
std::string frame_id_;
@@ -247,7 +247,7 @@
img_pub_.advertise("~image");
if (calibrated_) {
rect_pub_.advertise("~image_rect");
- info_pub_ = nh_.advertise<sensor_msgs::CamInfo>("~cam_info", 1);
+ info_pub_ = nh_.advertise<sensor_msgs::CameraInfo>("~cam_info", 1);
info_srv_ = nh_.advertiseService<>("~cam_info_service", &ProsilicaNode::camInfoService, this);
}
@@ -486,8 +486,8 @@
return true;
}
- bool camInfoService(prosilica_cam::CamInfo::Request &req,
- prosilica_cam::CamInfo::Response &res)
+ bool camInfoService(prosilica_cam::CameraInfo::Request &req,
+ prosilica_cam::CameraInfo::Response &res)
{
res.cam_info = cam_info_;
res.cam_info.header.stamp = ros::Time::now();
@@ -608,7 +608,7 @@
}
bool rectifyFrame(tPvFrame* frame, sensor_msgs::Image &img, sensor_msgs::Image &rect_img,
- sensor_msgs::CamInfo &cam_info)
+ sensor_msgs::CameraInfo &cam_info)
{
// Currently assume BGR format so bridge.toIpl() image points to msg data buffer
if (img.encoding != "bgr") {
@@ -632,14 +632,14 @@
assert(frame->RegionX == 0 && frame->RegionY == 0);
model_.undistort(raw, rect);
- model_.fillCamInfo(cam_info);
+ model_.fillCameraInfo(cam_info);
}
else {
camera_calibration::PinholeCameraModel roi_model =
m...
[truncated message content] |