Model of a camera on a kinematic chain. More...
#include <camera3d.h>
Public Member Functions | |
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). 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 () |
![]() | |
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_ |
![]() | |
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, |
const std::string & | param_name, | ||
KDL::Tree | model, | ||
std::string | root, | ||
std::string | tip | ||
) |
Create a new camera 3d model (Kinect/Primesense).
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. |
Definition at line 162 of file models.cpp.
|
inlinevirtual |
Definition at line 44 of file camera3d.h.
|
virtual |
Get the type for this model.
Reimplemented from robot_calibration::ChainModel.
Definition at line 264 of file models.cpp.
|
virtual |
Compute the updated positions of the observed points.
Reimplemented from robot_calibration::ChainModel.
Definition at line 169 of file models.cpp.
|
protected |
Definition at line 59 of file camera3d.h.