20 #include <mavros_msgs/ESCTelemetryItem.h> 30 mavros_msgs::ESCTelemetryItem escStatusMsg;
35 escStatusMsg.temperature = 300;
36 escStatusMsg.voltage = 50.0 - rpm[
nextEscIdx_] * 0.001;
37 escStatusMsg.current = 0.1 + rpm[
nextEscIdx_] * 0.001;
38 escStatusMsg.rpm =
static_cast<int>(rpm[
nextEscIdx_]);
bool publish(const std::vector< double > &rpm)
ros::NodeHandle * node_handler_
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
EscStatusSensor(ros::NodeHandle *nh, const char *topic, double period)
ros::Publisher publisher_