Class Camera2dModel
- Defined in File camera2d.hpp 
Inheritance Relationships
Base Type
- public robot_calibration::Chain3dModel(Class Chain3dModel)
Class Documentation
- 
class Camera2dModel : public robot_calibration::Chain3dModel
- Model of a camera on a kinematic chain. - Public Functions - 
Camera2dModel(const std::string &name, const std::string ¶m_name, KDL::Tree model, std::string root, std::string tip)
- Create a new camera 2d model. - Parameters:
- name – The name for this sensor, will be be used to select observations 
- param_name – The name to use when finding camera parameters, often the same as name 
- model – The KDL model of the robot’s kinematics. 
- root – The name of the root link, must be consistent across all models used for error modeling. Usually ‘base_link’. 
- tip – The tip of the chain. 
 
 
 - 
inline virtual ~Camera2dModel()
 - 
virtual std::vector<geometry_msgs::msg::PointStamped> project(const robot_calibration_msgs::msg::CalibrationData &data, const OptimizationOffsets &offsets)
- Compute the updated positions of the observed points. 
 - 
virtual std::vector<geometry_msgs::msg::PointStamped> project_pixel_error(const robot_calibration_msgs::msg::CalibrationData &data, const std::vector<geometry_msgs::msg::PointStamped> &points, const OptimizationOffsets &offsets)
- Compute the pixel coordinates of 3d coordinates, using camera model. 
 - 
virtual std::string getType() const
- Get the type for this model. 
 - Protected Attributes - 
std::string param_name_
 
- 
Camera2dModel(const std::string &name, const std::string ¶m_name, KDL::Tree model, std::string root, std::string tip)