Public Member Functions | Protected Attributes | List of all members
robot_calibration::Camera3dModel Class Reference

Model of a camera on a kinematic chain. More...

#include <camera3d.h>

Inheritance diagram for robot_calibration::Camera3dModel:
Inheritance graph
[legend]

Public Member Functions

 Camera3dModel (const std::string &name, const std::string &param_name, KDL::Tree model, std::string root, std::string tip)
 Create a new camera 3d model (Kinect/Primesense). More...
 
virtual std::string getType () const
 Get the type for this model. More...
 
virtual std::vector< geometry_msgs::PointStamped > project (const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
 Compute the updated positions of the observed points. More...
 
virtual ~Camera3dModel ()
 
- Public Member Functions inherited from robot_calibration::ChainModel
 ChainModel (const std::string &name, KDL::Tree model, std::string root, std::string tip)
 Create a new chain model. More...
 
KDL::Frame getChainFK (const CalibrationOffsetParser &offsets, const sensor_msgs::JointState &state)
 Compute the forward kinematics of the chain, based on the offsets and the joint positions of the state message. More...
 
virtual std::string getName () const
 Get the name of this model (as provided in the YAML config) More...
 
virtual ~ChainModel ()
 

Protected Attributes

std::string param_name_
 
- Protected Attributes inherited from robot_calibration::ChainModel
std::string name_
 
std::string root_
 
std::string tip_
 

Detailed Description

Model of a camera on a kinematic chain.

Definition at line 31 of file camera3d.h.

Constructor & Destructor Documentation

◆ Camera3dModel()

robot_calibration::Camera3dModel::Camera3dModel ( const std::string &  name,
const std::string &  param_name,
KDL::Tree  model,
std::string  root,
std::string  tip 
)

Create a new camera 3d model (Kinect/Primesense).

Parameters
nameThe name for this sensor, will be be used to select observations
param_nameThe name to use when finding camera parameters, often the same as name
modelThe KDL model of the robot's kinematics.
rootThe name of the root link, must be consistent across all models used for error modeling. Usually 'base_link'.
tipThe tip of the chain.

Definition at line 162 of file models.cpp.

◆ ~Camera3dModel()

virtual robot_calibration::Camera3dModel::~Camera3dModel ( )
inlinevirtual

Definition at line 44 of file camera3d.h.

Member Function Documentation

◆ getType()

std::string robot_calibration::Camera3dModel::getType ( ) const
virtual

Get the type for this model.

Reimplemented from robot_calibration::ChainModel.

Definition at line 264 of file models.cpp.

◆ project()

std::vector< geometry_msgs::PointStamped > robot_calibration::Camera3dModel::project ( const robot_calibration_msgs::CalibrationData &  data,
const CalibrationOffsetParser offsets 
)
virtual

Compute the updated positions of the observed points.

Reimplemented from robot_calibration::ChainModel.

Definition at line 169 of file models.cpp.

Member Data Documentation

◆ param_name_

std::string robot_calibration::Camera3dModel::param_name_
protected

Definition at line 59 of file camera3d.h.


The documentation for this class was generated from the following files:


robot_calibration
Author(s): Michael Ferguson
autogenerated on Wed May 24 2023 02:30:23