ice.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020-2022 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 #ifndef SRC_SENSORS_ICE_HPP
20 #define SRC_SENSORS_ICE_HPP
21 
22 #include "sensor_base.hpp"
23 
24 class IceStatusSensor : public BaseSensor{
25  public:
26  IceStatusSensor(ros::NodeHandle* nh, const char* topic, double period);
27  bool publish(double rpm);
28  void start_stall_emulation();
29  void stop_stall_emulation();
30  private:
31  void estimate_state(double rpm);
32  void emulate_normal_mode(double rpm);
33  void emulate_stall_mode();
34 
36 
37  double _rpm{0};
38  uint8_t _state{0};
39  double _stallTsMs = 0;
40  double _startTsSec = 0;
41 };
42 
43 #endif // SRC_SENSORS_ICE_HPP
bool publish(double rpm)
Definition: ice.cpp:37
IceStatusSensor(ros::NodeHandle *nh, const char *topic, double period)
Definition: ice.cpp:30
void emulate_normal_mode(double rpm)
Definition: ice.cpp:62
void start_stall_emulation()
Definition: ice.cpp:93
double _rpm
Definition: ice.hpp:37
double _stallTsMs
Definition: ice.hpp:39
uint8_t _state
Definition: ice.hpp:38
void estimate_state(double rpm)
Definition: ice.cpp:54
double _startTsSec
Definition: ice.hpp:40
ros::Publisher _status_publisher
Definition: ice.hpp:35
void emulate_stall_mode()
Definition: ice.cpp:75
void stop_stall_emulation()
Definition: ice.cpp:97


inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Sat Jul 1 2023 02:13:44