Class that caches and updates transformations for given frames. More...
#include <transform_provider.h>
Classes | |
class | 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 More... | |
bool | getTransform (mesh_filter::MeshHandle handle, Eigen::Isometry3d &transform) const |
returns the current transformation of a mesh given by its handle More... | |
void | setFrame (const std::string &frame) |
sets the camera frame id. The returned transformations are in respect to this coordinate frame More... | |
void | setUpdateRate (double update_rate) |
sets the update rate in Hz. This should be slow enough to reduce the system load but fast enough to get up-to-date transformations. For PSDK compatible devices this value should be around 30 Hz. More... | |
void | start () |
starts the updating process. Done in a seperate thread More... | |
void | stop () |
stops the update process/thread. More... | |
TransformProvider (double update_rate=30.) | |
Constructor. More... | |
~TransformProvider () | |
Destructor. More... | |
Private Member Functions | |
MOVEIT_CLASS_FORWARD (TransformContext) | |
void | run () |
The entry point of the dedicated thread that updates the transformations periodically. More... | |
void | updateTransforms () |
this method is called periodically by the dedicated thread and updates all the transformations of the registered frames. More... | |
Private Attributes | |
std::string | frame_id_ |
the camera frame id More... | |
std::map< mesh_filter::MeshHandle, TransformContextPtr > | handle2context_ |
mapping between the mesh handle and its context More... | |
planning_scene_monitor::PlanningSceneMonitorPtr | psm_ |
SceneMonitor used to get current states. More... | |
bool | stop_ |
std::shared_ptr< tf2_ros::Buffer > | tf_buffer_ |
std::shared_ptr< tf2_ros::TransformListener > | tf_listener_ |
TransformListener used to listen and update transformations. More... | |
std::thread | thread_ |
thread object More... | |
ros::Rate | update_rate_ |
update rate in Hz More... | |
Class that caches and updates transformations for given frames.
Definition at line 55 of file transform_provider.h.
TransformProvider::TransformProvider | ( | double | update_rate = 30. | ) |
Constructor.
[in] | update_rate | update rate in Hz |
Definition at line 42 of file transform_provider.cpp.
TransformProvider::~TransformProvider | ( | ) |
Destructor.
Definition at line 50 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 the mesh |
Definition at line 67 of file transform_provider.cpp.
bool TransformProvider::getTransform | ( | mesh_filter::MeshHandle | handle, |
Eigen::Isometry3d & | 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 90 of file transform_provider.cpp.
|
private |
|
private |
The entry point of the dedicated thread that updates the transformations periodically.
Definition at line 105 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 75 of file transform_provider.cpp.
void TransformProvider::setUpdateRate | ( | double | update_rate | ) |
sets the update rate in Hz. This should be slow enough to reduce the system load but fast enough to get up-to-date transformations. For PSDK compatible devices this value should be around 30 Hz.
[in] | update_rate | update rate in Hz |
Definition at line 117 of file transform_provider.cpp.
void TransformProvider::start | ( | ) |
starts the updating process. Done in a seperate thread
Definition at line 55 of file transform_provider.cpp.
void TransformProvider::stop | ( | ) |
stops the update process/thread.
Definition at line 61 of file transform_provider.cpp.
|
private |
this method is called periodically by the dedicated thread and updates all the transformations of the registered frames.
Definition at line 122 of file transform_provider.cpp.
|
private |
the camera frame id
Definition at line 156 of file transform_provider.h.
|
private |
mapping between the mesh handle and its context
Definition at line 146 of file transform_provider.h.
|
private |
SceneMonitor used to get current states.
Definition at line 153 of file transform_provider.h.
|
private |
\flag to leave the update loop
Definition at line 162 of file transform_provider.h.
|
private |
Definition at line 150 of file transform_provider.h.
|
private |
TransformListener used to listen and update transformations.
Definition at line 149 of file transform_provider.h.
|
private |
thread object
Definition at line 159 of file transform_provider.h.
|
private |
update rate in Hz
Definition at line 165 of file transform_provider.h.