This class is a ROS node allowing us to parametrize the connection to a Qualisys system and export the streamed objects to /tf and /tf_static. More...
#include <ros-qualisys/qualisys-to-ros.hpp>
Public Member Functions | |
QualisysToRos () | |
Construct a new Qualisys To Ros object, this a simple default constructor. More... | |
~QualisysToRos () | |
Destroy the Qualisys To Ros object. More... | |
void | setNodeHandle (ros::NodeHandle &nh) |
Set the Node Handle object. More... | |
bool | initialize () |
Initialize the object by: More... | |
void | run () |
Acquire the data from the Qualisys stream and send it back to the /tf or /tf_static topic. More... | |
void | terminate () |
Properly shutdown the connection with the Qualisys system. More... | |
This class is a ROS node allowing us to parametrize the connection to a Qualisys system and export the streamed objects to /tf and /tf_static.
We use rosparams in order to parametrize this nodes behavior. In order to find out the values of these parameters please refer to your Qualisys system documentation.
A quick example of YAML file for the parametrization.
A practical example is available for a real setup in LAAS-CNRS in ros-qualisys/config/bauzil-qualisys.yaml file.
ros_qualisys::QualisysToRos::QualisysToRos | ( | ) |
Construct a new Qualisys To Ros object, this a simple default constructor.
ros_qualisys::QualisysToRos::~QualisysToRos | ( | ) |
Destroy the Qualisys To Ros object.
bool ros_qualisys::QualisysToRos::initialize | ( | ) |
Initialize the object by:
void ros_qualisys::QualisysToRos::run | ( | ) |
Acquire the data from the Qualisys stream and send it back to the /tf or /tf_static topic.
void ros_qualisys::QualisysToRos::setNodeHandle | ( | ros::NodeHandle & | nh | ) |
Set the Node Handle object.
nh | pointer to a node handle. |
void ros_qualisys::QualisysToRos::terminate | ( | ) |
Properly shutdown the connection with the Qualisys system.