include
ensenso_camera
virtual_object_handler.h
Go to the documentation of this file.
1
#pragma once
2
3
#include "
ensenso_camera/ros2/node_handle.h
"
4
5
#include <
tf2_ros/buffer.h
>
6
#include <
tf2_ros/transform_listener.h
>
7
#include <
tf2/LinearMath/Transform.h
>
8
9
#include <atomic>
10
#include <thread>
11
#include <vector>
12
13
namespace
ensenso_camera
14
{
15
class
VirtualObjectHandler
16
{
17
public
:
18
VirtualObjectHandler
(
ensenso::ros::NodeHandle
& nh,
const
std::string& filename,
const
std::string&
objectsFrame
,
19
const
std::string&
linkFrame
,
const
std::string& markerTopic,
double
markerPublishRate);
20
~VirtualObjectHandler
();
21
22
void
updateObjectLinks
();
23
24
private
:
25
std::thread
markerThread
;
26
std::atomic_bool
stopMarkerThread
{
false
};
27
29
std::vector<tf2::Transform>
originalTransforms
;
30
31
std::string
objectsFrame
;
32
std::string
linkFrame
;
33
34
tf2_ros::Buffer
tfBuffer
;
35
tf2_ros::TransformListener
tfListener
{
tfBuffer
};
36
};
37
}
// namespace ensenso_camera
ensenso_camera::VirtualObjectHandler
Definition:
virtual_object_handler.h:15
ensenso_camera::VirtualObjectHandler::linkFrame
std::string linkFrame
Link frame where NxLib expects the objects to be defined.
Definition:
virtual_object_handler.h:32
ensenso_camera::VirtualObjectHandler::markerThread
std::thread markerThread
Background thread used to publish object markers.
Definition:
virtual_object_handler.h:25
ensenso_camera::VirtualObjectHandler::~VirtualObjectHandler
~VirtualObjectHandler()
Definition:
virtual_object_handler.cpp:187
ensenso_camera::VirtualObjectHandler::tfListener
tf2_ros::TransformListener tfListener
Definition:
virtual_object_handler.h:35
buffer.h
ensenso_camera::VirtualObjectHandler::tfBuffer
tf2_ros::Buffer tfBuffer
Definition:
virtual_object_handler.h:34
tf2_ros::TransformListener
ensenso_camera::VirtualObjectHandler::originalTransforms
std::vector< tf2::Transform > originalTransforms
Original object transforms in the base frame.
Definition:
virtual_object_handler.h:29
ensenso_camera::VirtualObjectHandler::stopMarkerThread
std::atomic_bool stopMarkerThread
Flag to indicate markerThread should stop.
Definition:
virtual_object_handler.h:26
ensenso::ros::NodeHandle
::ros::NodeHandle NodeHandle
Definition:
node.h:215
tf2_ros::Buffer
transform_listener.h
ensenso_camera
Definition:
mono_camera_node.h:9
ensenso_camera::VirtualObjectHandler::objectsFrame
std::string objectsFrame
Frame in which objects are defined.
Definition:
virtual_object_handler.h:31
ensenso_camera::VirtualObjectHandler::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:
virtual_object_handler.cpp:161
ensenso_camera::VirtualObjectHandler::updateObjectLinks
void updateObjectLinks()
Definition:
virtual_object_handler.cpp:197
node_handle.h
Transform.h
ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46