Debug data publisher. Supports adding/updating named variables and batch publishing.
More...
#include <DebugDataPublisher.h>
|
| | DebugDataPublisher (ros::NodeHandle &nh, const std::string &topic="debug_data", int queue_size=5) |
| | Construct and initialize the publisher.
|
| |
| void | add (const std::string &name, double value) |
| | Add or update a debug variable, stamped at current time.
|
| |
| void | add (const std::string &name, double value, const ros::Time &stamp) |
| | Add or update a debug variable with a custom timestamp.
|
| |
| void | publish () |
| | Publish accumulated debug data and clear.
|
| |
| void | publishAndKeep () |
| | Publish accumulated debug data without clearing. Useful for persistent variables.
|
| |
| void | clear () |
| | Clear all stored debug data.
|
| |
Debug data publisher. Supports adding/updating named variables and batch publishing.
◆ DebugDataPublisher()
| DebugDataPublisher::DebugDataPublisher |
( |
ros::NodeHandle & | nh, |
|
|
const std::string & | topic = "debug_data", |
|
|
int | queue_size = 5 ) |
|
inlineexplicit |
Construct and initialize the publisher.
- Parameters
-
| nh | ROS NodeHandle used for advertise. |
| topic | Topic name, defaults to "debug_data". |
| queue_size | Publish queue size, defaults to 5. |
◆ add() [1/2]
| void DebugDataPublisher::add |
( |
const std::string & | name, |
|
|
double | value ) |
|
inline |
Add or update a debug variable, stamped at current time.
- Parameters
-
| name | Variable name. Duplicates update the existing entry. |
| value | Variable value. |
◆ add() [2/2]
| void DebugDataPublisher::add |
( |
const std::string & | name, |
|
|
double | value, |
|
|
const ros::Time & | stamp ) |
|
inline |
Add or update a debug variable with a custom timestamp.
- Parameters
-
| name | Variable name. Duplicates update the existing entry. |
| value | Variable value. |
| stamp | Custom timestamp. |
◆ clear()
| void DebugDataPublisher::clear |
( |
| ) |
|
|
inline |
Clear all stored debug data.
◆ publish()
| void DebugDataPublisher::publish |
( |
| ) |
|
|
inline |
Publish accumulated debug data and clear.
◆ publishAndKeep()
| void DebugDataPublisher::publishAndKeep |
( |
| ) |
|
|
inline |
Publish accumulated debug data without clearing. Useful for persistent variables.
The documentation for this class was generated from the following file: