esc_status.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020-2023 RaccoonLab.
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License as published by
6  * the Free Software Foundation, version 3.
7  *
8  * This program is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
11  * General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * Author: Dmitry Ponomarev <ponomarevda96@gmail.com>
17  */
18 
19 #include "esc_status.hpp"
20 #include <mavros_msgs/ESCTelemetryItem.h>
21 
22 
23 EscStatusSensor::EscStatusSensor(ros::NodeHandle* nh, const char* topic, double period) : BaseSensor(nh, period){
24  publisher_ = node_handler_->advertise<mavros_msgs::ESCTelemetryItem>(topic, 10);
25 }
26 bool EscStatusSensor::publish(const std::vector<double>& rpm) {
28  auto crntTimeSec = ros::Time::now().toSec();
29  if(_isEnabled && !rpm.empty() && rpm.size() <= 8 && (nextPubTimeSec_ < crntTimeSec)){
30  mavros_msgs::ESCTelemetryItem escStatusMsg;
31  if(nextEscIdx_ >= rpm.size()){
32  nextEscIdx_ = 0;
33  }
34  escStatusMsg.count = nextEscIdx_;
35  escStatusMsg.temperature = 300;
36  escStatusMsg.voltage = 14.8 - rpm[nextEscIdx_] * 0.001;
37  escStatusMsg.current = 0.1 + rpm[nextEscIdx_] * 0.001;
38  escStatusMsg.rpm = static_cast<int>(rpm[nextEscIdx_]);
39  publisher_.publish(escStatusMsg);
40  nextPubTimeSec_ = crntTimeSec + PERIOD / (double)rpm.size();
41  nextEscIdx_++;
42  }
43  return true;
44 }
BaseSensor::_isEnabled
bool _isEnabled
Definition: sensor_base.hpp:33
TimeBase< Time, Duration >::toSec
double toSec() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
BaseSensor::publisher_
ros::Publisher publisher_
Definition: sensor_base.hpp:35
BaseSensor::nextPubTimeSec_
double nextPubTimeSec_
Definition: sensor_base.hpp:36
esc_status.hpp
EscStatusSensor::EscStatusSensor
EscStatusSensor(ros::NodeHandle *nh, const char *topic, double period)
Definition: esc_status.cpp:23
BaseSensor::PERIOD
const double PERIOD
Definition: sensor_base.hpp:34
BaseSensor
Definition: sensor_base.hpp:25
BaseSensor::node_handler_
ros::NodeHandle * node_handler_
Definition: sensor_base.hpp:32
EscStatusSensor::nextEscIdx_
uint8_t nextEscIdx_
Definition: esc_status.hpp:29
EscStatusSensor::publish
bool publish(const std::vector< double > &rpm)
Definition: esc_status.cpp:26
ros::NodeHandle
ros::Time::now
static Time now()


inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35