battery.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 "battery.hpp"
20 #include <sensor_msgs/BatteryState.h>
21 
22 BatteryInfoSensor::BatteryInfoSensor(ros::NodeHandle* nh, const char* topic, double period) : BaseSensor(nh, period){
23  publisher_ = node_handler_->advertise<sensor_msgs::BatteryState>(topic, 16);
24 }
25 bool BatteryInfoSensor::publish(float percentage) {
26  auto crntTimeSec = ros::Time::now().toSec();
27  if(_isEnabled && (nextPubTimeSec_ < crntTimeSec)){
28  // lipo 4s, 5 Ah
29  sensor_msgs::BatteryState batteryInfoMsg;
30  batteryInfoMsg.voltage = 14.8f; // Volts
31  batteryInfoMsg.current = 0.01f; // Ampers
32  batteryInfoMsg.temperature = 300.0f; // Kelvin
33  batteryInfoMsg.percentage = percentage; // 0 to 1 range
34  batteryInfoMsg.capacity = 5.0f; // Ah
35  batteryInfoMsg.design_capacity = batteryInfoMsg.capacity;
36  batteryInfoMsg.charge = percentage * batteryInfoMsg.capacity;
37  publisher_.publish(batteryInfoMsg);
38  nextPubTimeSec_ = crntTimeSec + PERIOD;
39  }
40  return true;
41 }
battery.hpp
BatteryInfoSensor::publish
bool publish(float percentage)
Definition: battery.cpp:25
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
BatteryInfoSensor::BatteryInfoSensor
BatteryInfoSensor(ros::NodeHandle *nh, const char *topic, double period)
Definition: battery.cpp:22
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
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