motor_trace_buffer.h
Go to the documentation of this file.
00001 
00027 #ifndef SR_EDC_ETHERCAT_DRIVERS_MOTOR_TRACE_BUFFER_H
00028 #define SR_EDC_ETHERCAT_DRIVERS_MOTOR_TRACE_BUFFER_H
00029 
00030 #include <sr_edc_ethercat_drivers/MotorTraceSample.h>
00031 #include <sr_edc_ethercat_drivers/ActuatorInfo.h>
00032 #include <sr_edc_ethercat_drivers/MotorTrace.h>
00033 
00034 #include <realtime_tools/realtime_publisher.h>
00035 #include <boost/thread/condition.hpp>  // Missing from realtime_publisher : wg-ros-pkg Ticket #4682
00036 #include <boost/utility.hpp>
00037 #include <string>
00038 #include <vector>
00039 
00040 namespace sr_edc_ethercat_drivers
00041 {
00050 class MotorTraceBuffer :
00051         private boost::noncopyable
00052 {
00053 public:
00054   explicit MotorTraceBuffer(unsigned trace_size);
00055 
00056   bool initialize(const sr_edc_ethercat_drivers::ActuatorInfo &actuator_info);
00057 
00058   void flagPublish(const std::string &reason, int level, int delay);
00059 
00060   void checkPublish();
00061 
00062   void sample(const sr_edc_ethercat_drivers::MotorTraceSample &s);
00063 
00064   void reset();
00065 
00066 protected:
00067   unsigned trace_size_;  // !< size of trace vector
00068   unsigned trace_index_;  // !< index of most recent element in trace vector
00069   unsigned published_traces_;  // !< number of times motor trace has been published
00070   std::vector<sr_edc_ethercat_drivers::MotorTraceSample> trace_buffer_;
00071   realtime_tools::RealtimePublisher<sr_edc_ethercat_drivers::MotorTrace> *publisher_;
00072   int publish_delay_;
00073   int publish_level_;
00074   std::string publish_reason_;
00075 };
00076 }  // namespace sr_edc_ethercat_drivers
00077 
00078 #endif  // SR_EDC_ETHERCAT_DRIVERS_MOTOR_TRACE_BUFFER_H


sr_edc_ethercat_drivers
Author(s): Ugo Cupcic, Yann Sionneau, Toni Oliver
autogenerated on Mon Jul 1 2019 20:06:31