main.hpp
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  * Authors: Dmitry Ponomarev <ponomarevda96@gmail.com>
17  * Roman Fedorenko <frontwise@gmail.com>
18  */
19 
20 #ifndef SRC_MAIN_HPP
21 #define SRC_MAIN_HPP
22 
23 #include <thread>
24 #include <random>
25 
26 #include <ros/ros.h>
27 #include <ros/time.h>
28 
29 #include <std_msgs/UInt8.h>
30 
31 #include "uavDynamicsSimBase.hpp"
32 #include "dynamics.hpp"
33 #include "actuators.hpp"
34 #include "sensors.hpp"
35 #include "scenarios.hpp"
36 #include "logger.hpp"
37 #include "rviz_visualization.hpp"
38 
39 
43 class Uav_Dynamics {
44  public:
45  explicit Uav_Dynamics(ros::NodeHandle nh);
46  int8_t init();
47 
48  private:
49  int8_t getParamsFromRos();
50  int8_t initDynamicsSimulator();
51  int8_t initSensors();
52  int8_t initCalibration();
53  int8_t startClockAndThreads();
54 
55  // Simulator
57  std::shared_ptr<UavDynamicsSimBase> uavDynamicsSim_;
59 
61  double dt_secs_ = 1.0f/960.;
62  double clockScale_ = 1.0;
64 
65  std::vector<double> initPose_{7};
66  std::vector<double> _wind_ned{3};
67 
69 
75 
76  // Calibration
79  void calibrationCallback(std_msgs::UInt8 msg);
80 
81  // Diagnostic
82  uint64_t dynamicsCounter_;
83  uint64_t rosPubCounter_;
84 
85  // Timer and threads
87  std::thread proceedDynamicsTask;
88  std::thread publishToRosTask;
89  std::thread diagnosticTask;
90 
92  void proceedDynamics(double period);
93  void publishToRos(double period);
94  void performLogging(double period);
95 
96  const float ROS_PUB_PERIOD_SEC = 0.05f;
97 };
98 
99 #endif // SRC_MAIN_HPP
UavDynamicsSimBase::SimMode_t
SimMode_t
Definition: uavDynamicsSimBase.hpp:57
Uav_Dynamics::_scenarioManager
ScenarioManager _scenarioManager
Definition: main.hpp:73
Uav_Dynamics::rosPubCounter_
uint64_t rosPubCounter_
Definition: main.hpp:83
Uav_Dynamics::initCalibration
int8_t initCalibration()
Definition: main.cpp:143
actuators.hpp
Uav_Dynamics::publishToRosTask
std::thread publishToRosTask
Definition: main.hpp:88
sensors.hpp
Uav_Dynamics::getParamsFromRos
int8_t getParamsFromRos()
Definition: main.cpp:80
ros::Publisher
Uav_Dynamics::Uav_Dynamics
Uav_Dynamics(ros::NodeHandle nh)
Definition: main.cpp:50
Uav_Dynamics::useSimTime_
bool useSimTime_
Definition: main.hpp:63
Uav_Dynamics::publishToRos
void publishToRos(double period)
Definition: main.cpp:257
Uav_Dynamics::currentTime_
ros::Time currentTime_
Definition: main.hpp:60
ros.h
Uav_Dynamics::diagnosticTask
std::thread diagnosticTask
Definition: main.hpp:89
time.h
Uav_Dynamics::proceedDynamics
void proceedDynamics(double period)
Definition: main.cpp:224
ros::WallTimer
Uav_Dynamics::initPose_
std::vector< double > initPose_
Definition: main.hpp:65
Uav_Dynamics::ROS_PUB_PERIOD_SEC
const float ROS_PUB_PERIOD_SEC
Definition: main.hpp:96
UavDynamicsSimBase::SimMode_t::NORMAL
@ NORMAL
RvizVisualizator
Definition: rviz_visualization.hpp:27
Actuators
Definition: actuators.hpp:33
Uav_Dynamics::startClockAndThreads
int8_t startClockAndThreads()
Definition: main.cpp:148
uavDynamicsSimBase.hpp
Uav_Dynamics::uavDynamicsSim_
std::shared_ptr< UavDynamicsSimBase > uavDynamicsSim_
Definition: main.hpp:57
Uav_Dynamics::info
DynamicsInfo info
Definition: main.hpp:68
Uav_Dynamics::clockScale_
double clockScale_
Definition: main.hpp:62
Uav_Dynamics::dynamicsCounter_
uint64_t dynamicsCounter_
Definition: main.hpp:82
Uav_Dynamics::clockPub_
ros::Publisher clockPub_
Definition: main.hpp:58
Sensors
Definition: sensors.hpp:37
Uav_Dynamics::initSensors
int8_t initSensors()
Definition: main.cpp:136
Uav_Dynamics::_logger
StateLogger _logger
Definition: main.hpp:74
StateLogger
Definition: logger.hpp:26
Uav_Dynamics::simulationLoopTimerCallback
void simulationLoopTimerCallback(const ros::WallTimerEvent &event)
Main Simulator loop.
Definition: main.cpp:182
Uav_Dynamics
UAV Dynamics class used for dynamics, IMU, and angular rate control simulation node.
Definition: main.hpp:43
scenarios.hpp
Uav_Dynamics::calibrationType_
UavDynamicsSimBase::SimMode_t calibrationType_
Definition: main.hpp:78
ros::WallTimerEvent
ros::Time
Uav_Dynamics::_actuators
Actuators _actuators
Definition: main.hpp:70
Uav_Dynamics::_wind_ned
std::vector< double > _wind_ned
Definition: main.hpp:66
Uav_Dynamics::_sensors
Sensors _sensors
Definition: main.hpp:71
Uav_Dynamics::simulationLoopTimer_
ros::WallTimer simulationLoopTimer_
Definition: main.hpp:86
logger.hpp
Uav_Dynamics::calibrationCallback
void calibrationCallback(std_msgs::UInt8 msg)
Definition: main.cpp:278
Uav_Dynamics::_node
ros::NodeHandle _node
Definition: main.hpp:56
ScenarioManager
Definition: scenarios.hpp:47
Uav_Dynamics::dt_secs_
double dt_secs_
Definition: main.hpp:61
Uav_Dynamics::init
int8_t init()
Definition: main.cpp:62
DynamicsInfo
Definition: dynamics.hpp:39
Uav_Dynamics::_rviz_visualizator
RvizVisualizator _rviz_visualizator
Definition: main.hpp:72
Uav_Dynamics::proceedDynamicsTask
std::thread proceedDynamicsTask
Definition: main.hpp:87
Uav_Dynamics::performLogging
void performLogging(double period)
Definition: main.cpp:195
ros::NodeHandle
ros::Subscriber
Uav_Dynamics::calibrationSub_
ros::Subscriber calibrationSub_
Definition: main.hpp:77
dynamics.hpp
Uav_Dynamics::initDynamicsSimulator
int8_t initDynamicsSimulator()
Definition: main.cpp:93
rviz_visualization.hpp


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