Main Page
Namespaces
Classes
Files
File List
File Members
include
robot_calibration
camera_info.h
Go to the documentation of this file.
1
/*
2
* Copyright (C) 2015 Fetch Robotics Inc.
3
* Copyright (C) 2013-2014 Unbounded Robotics Inc.
4
*
5
* Licensed under the Apache License, Version 2.0 (the "License");
6
* you may not use this file except in compliance with the License.
7
* You may obtain a copy of the License at
8
*
9
* http://www.apache.org/licenses/LICENSE-2.0
10
*
11
* Unless required by applicable law or agreed to in writing, software
12
* distributed under the License is distributed on an "AS IS" BASIS,
13
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14
* See the License for the specific language governing permissions and
15
* limitations under the License.
16
*/
17
18
// Author: Michael Ferguson
19
20
#ifndef ROBOT_CALIBRATION_CAMERA_INFO_H
21
#define ROBOT_CALIBRATION_CAMERA_INFO_H
22
23
#include <
ros/ros.h
>
24
#include <sensor_msgs/CameraInfo.h>
25
26
namespace
robot_calibration
27
{
28
29
enum
{
CAMERA_INFO_P_FX_INDEX
=0,
30
CAMERA_INFO_P_FY_INDEX
=5,
31
CAMERA_INFO_P_CX_INDEX
=2,
32
CAMERA_INFO_P_CY_INDEX
=6};
33
34
enum
{
CAMERA_INFO_K_FX_INDEX
=0,
35
CAMERA_INFO_K_FY_INDEX
=4,
36
CAMERA_INFO_K_CX_INDEX
=2,
37
CAMERA_INFO_K_CY_INDEX
=5};
38
39
enum
{
CAMERA_INFO_D_1
=0,
40
CAMERA_INFO_D_2
=1,
41
CAMERA_INFO_D_3
=2,
42
CAMERA_INFO_D_4
=3,
43
CAMERA_INFO_D_5
=4};
44
45
enum
{
CAMERA_PARAMS_CX_INDEX
=0,
46
CAMERA_PARAMS_CY_INDEX
=1,
47
CAMERA_PARAMS_FX_INDEX
=2,
48
CAMERA_PARAMS_FY_INDEX
=3,
49
CAMERA_PARAMS_Z_SCALE_INDEX
=4,
50
CAMERA_PARAMS_Z_OFFSET_INDEX
=5};
51
52
54
inline
sensor_msgs::CameraInfo
updateCameraInfo
(
double
camera_fx,
double
camera_fy,
55
double
camera_cx,
double
camera_cy,
56
const
sensor_msgs::CameraInfo& info)
57
{
58
sensor_msgs::CameraInfo new_info = info;
59
60
new_info.P[
CAMERA_INFO_P_CX_INDEX
] *= camera_cx + 1.0;
// CX
61
new_info.P[
CAMERA_INFO_P_CY_INDEX
] *= camera_cy + 1.0;
// CY
62
new_info.P[
CAMERA_INFO_P_FX_INDEX
] *= camera_fx + 1.0;
// FX
63
new_info.P[
CAMERA_INFO_P_FY_INDEX
] *= camera_fy + 1.0;
// FY
64
65
new_info.K[
CAMERA_INFO_K_CX_INDEX
] *= camera_cx + 1.0;
// CX
66
new_info.K[
CAMERA_INFO_K_CY_INDEX
] *= camera_cy + 1.0;
// CY
67
new_info.K[
CAMERA_INFO_K_FX_INDEX
] *= camera_fx + 1.0;
// FX
68
new_info.K[
CAMERA_INFO_K_FY_INDEX
] *= camera_fy + 1.0;
// FY
69
70
return
new_info;
71
}
72
73
}
// namespace robot_calibration
74
75
#endif // ROBOT_CALIBRATION_CAMERA_INFO_H
robot_calibration::CAMERA_PARAMS_CY_INDEX
Definition:
camera_info.h:46
robot_calibration::CAMERA_PARAMS_FY_INDEX
Definition:
camera_info.h:48
robot_calibration::updateCameraInfo
sensor_msgs::CameraInfo updateCameraInfo(double camera_fx, double camera_fy, double camera_cx, double camera_cy, const sensor_msgs::CameraInfo &info)
Update the camera calibration with the new offsets.
Definition:
camera_info.h:54
robot_calibration::CAMERA_INFO_D_1
Definition:
camera_info.h:39
robot_calibration::CAMERA_PARAMS_Z_SCALE_INDEX
Definition:
camera_info.h:49
robot_calibration::CAMERA_INFO_P_FY_INDEX
Definition:
camera_info.h:30
robot_calibration::CAMERA_INFO_K_CY_INDEX
Definition:
camera_info.h:37
robot_calibration::CAMERA_INFO_P_CY_INDEX
Definition:
camera_info.h:32
robot_calibration::CAMERA_PARAMS_FX_INDEX
Definition:
camera_info.h:47
robot_calibration::CAMERA_INFO_D_5
Definition:
camera_info.h:43
robot_calibration::CAMERA_PARAMS_CX_INDEX
Definition:
camera_info.h:45
robot_calibration
Calibration code lives under this namespace.
Definition:
calibration_offset_parser.h:25
robot_calibration::CAMERA_PARAMS_Z_OFFSET_INDEX
Definition:
camera_info.h:50
robot_calibration::CAMERA_INFO_D_4
Definition:
camera_info.h:42
robot_calibration::CAMERA_INFO_P_FX_INDEX
Definition:
camera_info.h:29
ros.h
robot_calibration::CAMERA_INFO_D_2
Definition:
camera_info.h:40
robot_calibration::CAMERA_INFO_D_3
Definition:
camera_info.h:41
robot_calibration::CAMERA_INFO_K_FX_INDEX
Definition:
camera_info.h:34
robot_calibration::CAMERA_INFO_K_CX_INDEX
Definition:
camera_info.h:36
robot_calibration::CAMERA_INFO_P_CX_INDEX
Definition:
camera_info.h:31
robot_calibration::CAMERA_INFO_K_FY_INDEX
Definition:
camera_info.h:35
robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30