26 #ifndef SR_EDC_ETHERCAT_DRIVERS_MOTOR_TRACE_BUFFER_H 27 #define SR_EDC_ETHERCAT_DRIVERS_MOTOR_TRACE_BUFFER_H 29 #include <sr_edc_ethercat_drivers/MotorTraceSample.h> 30 #include <sr_edc_ethercat_drivers/ActuatorInfo.h> 31 #include <sr_edc_ethercat_drivers/MotorTrace.h> 34 #include <boost/thread/condition.hpp> 35 #include <boost/utility.hpp> 50 private boost::noncopyable
55 bool initialize(
const sr_edc_ethercat_drivers::ActuatorInfo &actuator_info);
57 void flagPublish(
const std::string &reason,
int level,
int delay);
61 void sample(
const sr_edc_ethercat_drivers::MotorTraceSample &
s);
77 #endif // SR_EDC_ETHERCAT_DRIVERS_MOTOR_TRACE_BUFFER_H
void flagPublish(const std::string &reason, int level, int delay)
flags delayed publish of motor trace.
Class to buffer and publish previous 1-second of motor data.
void sample(const sr_edc_ethercat_drivers::MotorTraceSample &s)
Adds sample to motor trace.
bool initialize(const sr_edc_ethercat_drivers::ActuatorInfo &actuator_info)
Initializes motor trace publisher.
realtime_tools::RealtimePublisher< sr_edc_ethercat_drivers::MotorTrace > * publisher_
MotorTraceBuffer(unsigned trace_size)
unsigned published_traces_
void checkPublish()
Publishes motor trace if delay time is up.
std::string publish_reason_
std::vector< sr_edc_ethercat_drivers::MotorTraceSample > trace_buffer_