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 
24 
25 namespace robot_calibration
26 {
27 
31 class Camera3dModel : public ChainModel
32 {
33 public:
41  Camera3dModel(const std::string& name, KDL::Tree model, std::string root, std::string tip);
42  virtual ~Camera3dModel() {}
43 
47  virtual std::vector<geometry_msgs::PointStamped> project(
48  const robot_calibration_msgs::CalibrationData& data,
49  const CalibrationOffsetParser& offsets);
50 };
51 
52 } // namespace robot_calibration
53 
54 #endif // ROBOT_CALIBRATION_MODELS_CAMERA3D_H
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
Camera3dModel(const std::string &name, KDL::Tree model, std::string root, std::string tip)
Create a new camera 3d model (Kinect/Primesense).
Definition: models.cpp:147
Calibration code lives under this namespace.
Model of a camera on a kinematic chain.
Definition: camera3d.h:31
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:153
std::string name() const
Definition: chain.h:153
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 Tue Nov 3 2020 17:30:30