Public Member Functions
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]

List of all members.

Public Member Functions

 Camera3dModel (const std::string &name, KDL::Tree model, std::string root, std::string tip)
 Create a new camera 3d model (Kinect/Primesense).
virtual std::vector
< geometry_msgs::PointStamped > 
project (const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
 Compute the updated positions of the observed points.
virtual ~Camera3dModel ()

Detailed Description

Model of a camera on a kinematic chain.

Definition at line 31 of file camera3d.h.


Constructor & Destructor Documentation

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

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

Parameters:
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 134 of file models.cpp.

virtual robot_calibration::Camera3dModel::~Camera3dModel ( ) [inline, virtual]

Definition at line 42 of file camera3d.h.


Member Function Documentation

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 140 of file models.cpp.


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


robot_calibration
Author(s): Michael Ferguson
autogenerated on Thu Jun 6 2019 21:54:10