#include <virtual_object_handler.h>
Public Member Functions | |
void | updateObjectLinks () |
VirtualObjectHandler (ensenso::ros::NodeHandle &nh, const std::string &filename, const std::string &objectsFrame, const std::string &linkFrame, const std::string &markerTopic, double markerPublishRate) | |
~VirtualObjectHandler () | |
Private Attributes | |
std::string | linkFrame |
Link frame where NxLib expects the objects to be defined. More... | |
std::thread | markerThread |
Background thread used to publish object markers. More... | |
std::string | objectsFrame |
Frame in which objects are defined. More... | |
std::vector< tf2::Transform > | originalTransforms |
Original object transforms in the base frame. More... | |
std::atomic_bool | stopMarkerThread { false } |
Flag to indicate markerThread should stop. More... | |
tf2_ros::Buffer | tfBuffer |
tf2_ros::TransformListener | tfListener { tfBuffer } |
Definition at line 15 of file virtual_object_handler.h.
VirtualObjectHandler::VirtualObjectHandler | ( | ensenso::ros::NodeHandle & | nh, |
const std::string & | filename, | ||
const std::string & | objectsFrame, | ||
const std::string & | linkFrame, | ||
const std::string & | markerTopic, | ||
double | markerPublishRate | ||
) |
Definition at line 161 of file virtual_object_handler.cpp.
VirtualObjectHandler::~VirtualObjectHandler | ( | ) |
Definition at line 187 of file virtual_object_handler.cpp.
void VirtualObjectHandler::updateObjectLinks | ( | ) |
Definition at line 197 of file virtual_object_handler.cpp.
|
private |
Link frame where NxLib expects the objects to be defined.
Definition at line 32 of file virtual_object_handler.h.
|
private |
Background thread used to publish object markers.
Definition at line 25 of file virtual_object_handler.h.
|
private |
Frame in which objects are defined.
Definition at line 31 of file virtual_object_handler.h.
|
private |
Original object transforms in the base frame.
Definition at line 29 of file virtual_object_handler.h.
|
private |
Flag to indicate markerThread should stop.
Definition at line 26 of file virtual_object_handler.h.
|
private |
Definition at line 34 of file virtual_object_handler.h.
|
private |
Definition at line 35 of file virtual_object_handler.h.