Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
TransformProvider Class Reference

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::Buffertf_buffer_
 
std::shared_ptr< tf2_ros::TransformListenertf_listener_
 TransformListener used to listen and update transformations. More...
 
std::thread thread_
 thread object More...
 
ros::Rate update_rate_
 update rate in Hz More...
 

Detailed Description

Class that caches and updates transformations for given frames.

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)

Definition at line 55 of file transform_provider.h.

Constructor & Destructor Documentation

◆ TransformProvider()

TransformProvider::TransformProvider ( double  update_rate = 30.)

Constructor.

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
Parameters
[in]update_rateupdate rate in Hz

Definition at line 42 of file transform_provider.cpp.

◆ ~TransformProvider()

TransformProvider::~TransformProvider ( )

Destructor.

Definition at line 50 of file transform_provider.cpp.

Member Function Documentation

◆ addHandle()

void TransformProvider::addHandle ( mesh_filter::MeshHandle  handle,
const std::string &  name 
)

registers a mesh with its handle

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
Parameters
[in]handlehandle of the mesh
[in]nameframe_id_ of the mesh

Definition at line 67 of file transform_provider.cpp.

◆ getTransform()

bool TransformProvider::getTransform ( mesh_filter::MeshHandle  handle,
Eigen::Isometry3d &  transform 
) const

returns the current transformation of a mesh given by its handle

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
Parameters
[in]handlehandle of the mesh
[out]transformpose of the mesh in camera coordinate system
Returns
true if transform available, false otherwise

Definition at line 90 of file transform_provider.cpp.

◆ MOVEIT_CLASS_FORWARD()

TransformProvider::MOVEIT_CLASS_FORWARD ( TransformContext  )
private

◆ run()

void TransformProvider::run ( )
private

The entry point of the dedicated thread that updates the transformations periodically.

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)

Definition at line 105 of file transform_provider.cpp.

◆ setFrame()

void TransformProvider::setFrame ( const std::string &  frame)

sets the camera frame id. The returned transformations are in respect to this coordinate frame

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
Parameters
frameframe id of parent/camera coordinate system.

Definition at line 75 of file transform_provider.cpp.

◆ setUpdateRate()

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.

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
Parameters
[in]update_rateupdate rate in Hz

Definition at line 117 of file transform_provider.cpp.

◆ start()

void TransformProvider::start ( )

starts the updating process. Done in a seperate thread

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)

Definition at line 55 of file transform_provider.cpp.

◆ stop()

void TransformProvider::stop ( )

stops the update process/thread.

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)

Definition at line 61 of file transform_provider.cpp.

◆ updateTransforms()

void TransformProvider::updateTransforms ( )
private

this method is called periodically by the dedicated thread and updates all the transformations of the registered frames.

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)

Definition at line 122 of file transform_provider.cpp.

Member Data Documentation

◆ frame_id_

std::string TransformProvider::frame_id_
private

the camera frame id

Definition at line 156 of file transform_provider.h.

◆ handle2context_

std::map<mesh_filter::MeshHandle, TransformContextPtr> TransformProvider::handle2context_
private

mapping between the mesh handle and its context

Definition at line 146 of file transform_provider.h.

◆ psm_

planning_scene_monitor::PlanningSceneMonitorPtr TransformProvider::psm_
private

SceneMonitor used to get current states.

Definition at line 153 of file transform_provider.h.

◆ stop_

bool TransformProvider::stop_
private

\flag to leave the update loop

Definition at line 162 of file transform_provider.h.

◆ tf_buffer_

std::shared_ptr<tf2_ros::Buffer> TransformProvider::tf_buffer_
private

Definition at line 150 of file transform_provider.h.

◆ tf_listener_

std::shared_ptr<tf2_ros::TransformListener> TransformProvider::tf_listener_
private

TransformListener used to listen and update transformations.

Definition at line 149 of file transform_provider.h.

◆ thread_

std::thread TransformProvider::thread_
private

thread object

Definition at line 159 of file transform_provider.h.

◆ update_rate_

ros::Rate TransformProvider::update_rate_
private

update rate in Hz

Definition at line 165 of file transform_provider.h.


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


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Thu Jun 27 2024 02:27:09