Go to the documentation of this file.
19 #ifndef ROBOT_CALIBRATION_MODELS_CAMERA3D_H
20 #define ROBOT_CALIBRATION_MODELS_CAMERA3D_H
43 Camera3dModel(
const std::string&
name,
const std::string& param_name, KDL::Tree model, std::string root, std::string tip);
49 virtual std::vector<geometry_msgs::PointStamped>
project(
50 const robot_calibration_msgs::CalibrationData& data,
56 virtual std::string
getType()
const;
64 #endif // ROBOT_CALIBRATION_MODELS_CAMERA3D_H
virtual std::string getType() const
Get the type for this model.
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
virtual std::vector< geometry_msgs::PointStamped > project(const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
Compute the updated positions of the observed points.
Calibration code lives under this namespace.
Model of a camera on a kinematic chain.
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).
Model of a kinematic chain. This is the basic instance where we transform the world observations into...
robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01