#include <esc_status.hpp>
Public Member Functions | |
EscStatusSensor (ros::NodeHandle *nh, const char *topic, double period) | |
bool | publish (const std::vector< double > &rpm) |
![]() | |
BaseSensor ()=delete | |
BaseSensor (ros::NodeHandle *nh, double period) | |
void | disable () |
void | enable () |
Private Attributes | |
uint8_t | nextEscIdx_ = 0 |
Additional Inherited Members | |
![]() | |
bool | _isEnabled {false} |
double | nextPubTimeSec_ = 0 |
ros::NodeHandle * | node_handler_ |
std::normal_distribution< double > | normalDistribution_ {std::normal_distribution<double>(0.0, 1.0)} |
const double | PERIOD |
ros::Publisher | publisher_ |
std::default_random_engine | randomGenerator_ |
Definition at line 24 of file esc_status.hpp.
EscStatusSensor::EscStatusSensor | ( | ros::NodeHandle * | nh, |
const char * | topic, | ||
double | period | ||
) |
Definition at line 23 of file esc_status.cpp.
bool EscStatusSensor::publish | ( | const std::vector< double > & | rpm | ) |
< The idea here is to publish each esc status with equal interval instead of burst
Definition at line 26 of file esc_status.cpp.
|
private |
Definition at line 29 of file esc_status.hpp.