Model of a camera on a kinematic chain. More...
#include <camera3d.h>
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). 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... | |
std::string | name () const |
virtual | ~ChainModel () |
Additional Inherited Members | |
Protected Attributes inherited from robot_calibration::ChainModel | |
std::string | name_ |
std::string | root_ |
std::string | tip_ |
Model of a camera on a kinematic chain.
Definition at line 31 of file camera3d.h.
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).
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. |
Definition at line 147 of file models.cpp.
|
inlinevirtual |
Definition at line 42 of file camera3d.h.
|
virtual |
Compute the updated positions of the observed points.
Reimplemented from robot_calibration::ChainModel.
Definition at line 153 of file models.cpp.