Class that caches and updates transformations for given frames. More...
#include <transform_provider.h>
Classes | |
struct | TransformContext |
Context Object for registered frames. More... | |
Public Member Functions | |
void | addHandle (mesh_filter::MeshHandle handle, const std::string &name) |
registers a mesh with its handle | |
bool | getTransform (mesh_filter::MeshHandle handle, Eigen::Affine3d &transform) const |
returns the current transformation of a mesh given by its handle | |
void | setFrame (const std::string &frame) |
sets the camera frame id. The returned transformations are in respect to this coordinate frame | |
void | setUpdateInterval (unsigned long usecs) |
sets the update interval in micro seconds. This should be low enough to reduce the system load but high enough to get up-to-date transformations. For PSDK compatible devices this value should be around 30000 = 30ms | |
void | start () |
starts the updating process. Done in a seperate thread | |
void | stop () |
stops the update process/thread. | |
TransformProvider (unsigned long interval_us=30000) | |
Constructor. | |
~TransformProvider () | |
Destructor. | |
Private Member Functions | |
void | run () |
The entry point of the dedicated thread that updates the transformations periodically. | |
void | updateTransforms () |
this method is called periodically by the dedicated thread and updates all the transformations of the registered frames. | |
Private Attributes | |
std::string | frame_id_ |
the camera frame id | |
std::map < mesh_filter::MeshHandle, boost::shared_ptr < TransformContext > > | handle2context_ |
mapping between the mesh handle and its context | |
unsigned long | interval_us_ |
update interval in micro seconds | |
planning_scene_monitor::PlanningSceneMonitorPtr | psm_ |
SceneMonitor used to get current states. | |
bool | stop_ |
boost::shared_ptr < tf::TransformListener > | tf_ |
TransformListener used to listen and update transformations. | |
boost::thread | thread_ |
thread object |
Class that caches and updates transformations for given frames.
Definition at line 57 of file transform_provider.h.
TransformProvider::TransformProvider | ( | unsigned long | interval_us = 30000 | ) |
Constructor.
[in] | interval_us | update interval in micro seconds |
Definition at line 47 of file transform_provider.cpp.
Destructor.
Definition at line 56 of file transform_provider.cpp.
void TransformProvider::addHandle | ( | mesh_filter::MeshHandle | handle, |
const std::string & | name | ||
) |
registers a mesh with its handle
[in] | handle | handle of the mesh |
[in] | name | frame_id_ of teh mesh |
Definition at line 73 of file transform_provider.cpp.
bool TransformProvider::getTransform | ( | mesh_filter::MeshHandle | handle, |
Eigen::Affine3d & | transform | ||
) | const |
returns the current transformation of a mesh given by its handle
[in] | handle | handle of the mesh |
[out] | transform | pose of the mesh in camera coordinate system |
Definition at line 96 of file transform_provider.cpp.
void TransformProvider::run | ( | ) | [private] |
The entry point of the dedicated thread that updates the transformations periodically.
Definition at line 111 of file transform_provider.cpp.
void TransformProvider::setFrame | ( | const std::string & | frame | ) |
sets the camera frame id. The returned transformations are in respect to this coordinate frame
frame | frame id of parent/camera coordinate system. |
Definition at line 81 of file transform_provider.cpp.
void TransformProvider::setUpdateInterval | ( | unsigned long | usecs | ) |
sets the update interval in micro seconds. This should be low enough to reduce the system load but high enough to get up-to-date transformations. For PSDK compatible devices this value should be around 30000 = 30ms
[in] | usecs | interval in micro seconds |
Definition at line 123 of file transform_provider.cpp.
void TransformProvider::start | ( | void | ) |
starts the updating process. Done in a seperate thread
Definition at line 61 of file transform_provider.cpp.
void TransformProvider::stop | ( | void | ) |
stops the update process/thread.
Definition at line 67 of file transform_provider.cpp.
void TransformProvider::updateTransforms | ( | ) | [private] |
this method is called periodically by the dedicated thread and updates all the transformations of the registered frames.
Definition at line 128 of file transform_provider.cpp.
std::string TransformProvider::frame_id_ [private] |
the camera frame id
Definition at line 153 of file transform_provider.h.
std:: map<mesh_filter::MeshHandle, boost::shared_ptr<TransformContext> > TransformProvider::handle2context_ [private] |
mapping between the mesh handle and its context
Definition at line 144 of file transform_provider.h.
unsigned long TransformProvider::interval_us_ [private] |
update interval in micro seconds
Definition at line 162 of file transform_provider.h.
planning_scene_monitor::PlanningSceneMonitorPtr TransformProvider::psm_ [private] |
SceneMonitor used to get current states.
Definition at line 150 of file transform_provider.h.
bool TransformProvider::stop_ [private] |
to leave the update loop
Definition at line 159 of file transform_provider.h.
boost::shared_ptr<tf::TransformListener> TransformProvider::tf_ [private] |
TransformListener used to listen and update transformations.
Definition at line 147 of file transform_provider.h.
boost::thread TransformProvider::thread_ [private] |
thread object
Definition at line 156 of file transform_provider.h.