rm_control
Loading...
Searching...
No Matches
DebugDataPublisher Class Reference

Debug data publisher. Supports adding/updating named variables and batch publishing. More...

#include <DebugDataPublisher.h>

Public Member Functions

 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.
 

Detailed Description

Debug data publisher. Supports adding/updating named variables and batch publishing.

Constructor & Destructor Documentation

◆ DebugDataPublisher()

DebugDataPublisher::DebugDataPublisher ( ros::NodeHandle & nh,
const std::string & topic = "debug_data",
int queue_size = 5 )
inlineexplicit

Construct and initialize the publisher.

Parameters
nhROS NodeHandle used for advertise.
topicTopic name, defaults to "debug_data".
queue_sizePublish queue size, defaults to 5.

Member Function Documentation

◆ add() [1/2]

void DebugDataPublisher::add ( const std::string & name,
double value )
inline

Add or update a debug variable, stamped at current time.

Parameters
nameVariable name. Duplicates update the existing entry.
valueVariable 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
nameVariable name. Duplicates update the existing entry.
valueVariable value.
stampCustom 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: