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 #ifndef ROBOT_CALIBRATION_CAMERA_INFO_H
00021 #define ROBOT_CALIBRATION_CAMERA_INFO_H
00022
00023 #include <ros/ros.h>
00024 #include <sensor_msgs/CameraInfo.h>
00025
00026 namespace robot_calibration
00027 {
00028
00029 enum {CAMERA_INFO_P_FX_INDEX=0,
00030 CAMERA_INFO_P_FY_INDEX=5,
00031 CAMERA_INFO_P_CX_INDEX=2,
00032 CAMERA_INFO_P_CY_INDEX=6};
00033
00034 enum {CAMERA_INFO_K_FX_INDEX=0,
00035 CAMERA_INFO_K_FY_INDEX=4,
00036 CAMERA_INFO_K_CX_INDEX=2,
00037 CAMERA_INFO_K_CY_INDEX=5};
00038
00039 enum {CAMERA_INFO_D_1=0,
00040 CAMERA_INFO_D_2=1,
00041 CAMERA_INFO_D_3=2,
00042 CAMERA_INFO_D_4=3,
00043 CAMERA_INFO_D_5=4};
00044
00045 enum {CAMERA_PARAMS_CX_INDEX=0,
00046 CAMERA_PARAMS_CY_INDEX=1,
00047 CAMERA_PARAMS_FX_INDEX=2,
00048 CAMERA_PARAMS_FY_INDEX=3,
00049 CAMERA_PARAMS_Z_SCALE_INDEX=4,
00050 CAMERA_PARAMS_Z_OFFSET_INDEX=5};
00051
00052
00054 inline sensor_msgs::CameraInfo updateCameraInfo(double camera_fx, double camera_fy,
00055 double camera_cx, double camera_cy,
00056 const sensor_msgs::CameraInfo& info)
00057 {
00058 sensor_msgs::CameraInfo new_info = info;
00059
00060 new_info.P[CAMERA_INFO_P_CX_INDEX] *= camera_cx + 1.0;
00061 new_info.P[CAMERA_INFO_P_CY_INDEX] *= camera_cy + 1.0;
00062 new_info.P[CAMERA_INFO_P_FX_INDEX] *= camera_fx + 1.0;
00063 new_info.P[CAMERA_INFO_P_FY_INDEX] *= camera_fy + 1.0;
00064
00065 new_info.K[CAMERA_INFO_K_CX_INDEX] = new_info.P[CAMERA_INFO_P_CX_INDEX];
00066 new_info.K[CAMERA_INFO_K_CY_INDEX] = new_info.P[CAMERA_INFO_P_CY_INDEX];
00067 new_info.K[CAMERA_INFO_K_FX_INDEX] = new_info.P[CAMERA_INFO_P_FX_INDEX];
00068 new_info.K[CAMERA_INFO_K_FY_INDEX] = new_info.P[CAMERA_INFO_P_FY_INDEX];
00069
00070 return new_info;
00071 }
00072
00073 }
00074
00075 #endif // ROBOT_CALIBRATION_CAMERA_INFO_H