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

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 More...
 
bool getTransform (mesh_filter::MeshHandle handle, Eigen::Affine3d &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 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 More...
 
void start ()
 starts the updating process. Done in a seperate thread More...
 
void stop ()
 stops the update process/thread. More...
 
 TransformProvider (unsigned long interval_us=30000)
 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...
 
unsigned long interval_us_
 update interval in micro seconds More...
 
planning_scene_monitor::PlanningSceneMonitorPtr psm_
 SceneMonitor used to get current states. More...
 
bool stop_
 
boost::shared_ptr< tf::TransformListenertf_
 TransformListener used to listen and update transformations. More...
 
boost::thread thread_
 thread object 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 58 of file transform_provider.h.

Constructor & Destructor Documentation

TransformProvider::TransformProvider ( unsigned long  interval_us = 30000)

Constructor.

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
Parameters
[in]interval_usupdate interval in micro seconds

Definition at line 47 of file transform_provider.cpp.

TransformProvider::~TransformProvider ( )

Destructor.

Definition at line 54 of file transform_provider.cpp.

Member Function Documentation

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 teh mesh

Definition at line 71 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

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 95 of file transform_provider.cpp.

TransformProvider::MOVEIT_CLASS_FORWARD ( TransformContext  )
private
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 110 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

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 79 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

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
Parameters
[in]usecsinterval in micro seconds

Definition at line 122 of file transform_provider.cpp.

void TransformProvider::start ( void  )

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 59 of file transform_provider.cpp.

void TransformProvider::stop ( void  )

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 65 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.

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

Definition at line 127 of file transform_provider.cpp.

Member Data Documentation

std::string TransformProvider::frame_id_
private

the camera frame id

Definition at line 158 of file transform_provider.h.

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

mapping between the mesh handle and its context

Definition at line 149 of file transform_provider.h.

unsigned long TransformProvider::interval_us_
private

update interval in micro seconds

Definition at line 167 of file transform_provider.h.

planning_scene_monitor::PlanningSceneMonitorPtr TransformProvider::psm_
private

SceneMonitor used to get current states.

Definition at line 155 of file transform_provider.h.

bool TransformProvider::stop_
private

to leave the update loop

Definition at line 164 of file transform_provider.h.

boost::shared_ptr<tf::TransformListener> TransformProvider::tf_
private

TransformListener used to listen and update transformations.

Definition at line 152 of file transform_provider.h.

boost::thread TransformProvider::thread_
private

thread object

Definition at line 161 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 Sun Oct 18 2020 13:17:23