Main Page
Namespaces
Namespace List
Namespace Members
All
a
b
c
d
e
f
g
h
l
m
p
r
s
u
x
y
z
Functions
Variables
Typedefs
Enumerator
Classes
Class List
Class Hierarchy
Class Members
All
a
b
c
d
e
f
g
h
i
j
l
m
n
o
p
r
s
t
u
v
w
x
y
z
~
Functions
a
b
c
d
e
f
g
h
i
l
m
o
p
r
s
u
w
~
Variables
a
b
c
d
e
f
h
i
j
l
m
n
o
p
r
s
t
u
v
w
x
y
z
Typedefs
Files
File List
File Members
All
Functions
Variables
Macros
include
robot_calibration
models
camera3d.h
Go to the documentation of this file.
1
/*
2
* Copyright (C) 2013-2014 Unbounded Robotics Inc.
3
*
4
* Licensed under the Apache License, Version 2.0 (the "License");
5
* you may not use this file except in compliance with the License.
6
* You may obtain a copy of the License at
7
*
8
* http://www.apache.org/licenses/LICENSE-2.0
9
*
10
* Unless required by applicable law or agreed to in writing, software
11
* distributed under the License is distributed on an "AS IS" BASIS,
12
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13
* See the License for the specific language governing permissions and
14
* limitations under the License.
15
*/
16
17
// Author: Michael Ferguson
18
19
#ifndef ROBOT_CALIBRATION_MODELS_CAMERA3D_H
20
#define ROBOT_CALIBRATION_MODELS_CAMERA3D_H
21
22
#include <
robot_calibration/camera_info.h
>
23
#include <
robot_calibration/models/chain.h
>
24
25
namespace
robot_calibration
26
{
27
31
class
Camera3dModel
:
public
ChainModel
32
{
33
public
:
43
Camera3dModel
(
const
std::string&
name
,
const
std::string& param_name, KDL::Tree model, std::string root, std::string tip);
44
virtual
~Camera3dModel
() {}
45
49
virtual
std::vector<geometry_msgs::PointStamped>
project
(
50
const
robot_calibration_msgs::CalibrationData& data,
51
const
CalibrationOffsetParser
& offsets);
52
56
virtual
std::string
getType
()
const
;
57
58
protected
:
59
std::string
param_name_
;
60
};
61
62
}
// namespace robot_calibration
63
64
#endif // ROBOT_CALIBRATION_MODELS_CAMERA3D_H
robot_calibration::Camera3dModel::getType
virtual std::string getType() const
Get the type for this model.
Definition:
models.cpp:264
robot_calibration::CalibrationOffsetParser
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
Definition:
offset_parser.h:33
robot_calibration::Camera3dModel::~Camera3dModel
virtual ~Camera3dModel()
Definition:
camera3d.h:44
robot_calibration::Camera3dModel::param_name_
std::string param_name_
Definition:
camera3d.h:59
name
std::string name
chain.h
robot_calibration::Camera3dModel::project
virtual std::vector< geometry_msgs::PointStamped > project(const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
Compute the updated positions of the observed points.
Definition:
models.cpp:169
robot_calibration
Calibration code lives under this namespace.
Definition:
base_calibration.h:28
camera_info.h
robot_calibration::Camera3dModel
Model of a camera on a kinematic chain.
Definition:
camera3d.h:31
robot_calibration::Camera3dModel::Camera3dModel
Camera3dModel(const std::string &name, const std::string ¶m_name, KDL::Tree model, std::string root, std::string tip)
Create a new camera 3d model (Kinect/Primesense).
Definition:
models.cpp:162
robot_calibration::ChainModel
Model of a kinematic chain. This is the basic instance where we transform the world observations into...
Definition:
chain.h:107
robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01