uavDynamicsSimBase.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  * Author: Dmitry Ponomarev <ponomarevda96@gmail.com>
17  */
18 
19 
20 #ifndef UAV_DYNAMICS_SIM_BASE_HPP
21 #define UAV_DYNAMICS_SIM_BASE_HPP
22 
23 #include <Eigen/Geometry>
24 #include <vector>
25 #include <ros/ros.h>
26 #include <geometry_msgs/TransformStamped.h>
28 
29 
31 public:
32  UavDynamicsSimBase() = default;
33  virtual ~UavDynamicsSimBase() = default;
34 
39  virtual int8_t init() = 0;
40  virtual void setInitialPosition(const Eigen::Vector3d & position,
41  const Eigen::Quaterniond& attitude) = 0;
42 
43  virtual void land() {
44  // do nothing by default
45  }
46  virtual void process(double dt_secs,
47  const std::vector<double> & motorSpeedCommandIn,
48  bool isCmdPercent) = 0;
49 
50  virtual Eigen::Vector3d getVehiclePosition() const = 0;
51  virtual Eigen::Quaterniond getVehicleAttitude() const = 0;
52  virtual Eigen::Vector3d getVehicleVelocity(void) const = 0;
53  virtual Eigen::Vector3d getVehicleAngularVelocity(void) const = 0;
54  virtual void getIMUMeasurement(Eigen::Vector3d & accOutput, Eigen::Vector3d & gyroOutput) = 0;
55  virtual bool getMotorsRpm(std::vector<double>& motorsRpm);
56 
57  enum class SimMode_t{
58  NORMAL = 0,
59 
60  MAG_1_NORMAL = 1, // ROLL OK ROTATE YAW POSITIVE
61  MAG_2_OVERTURNED = 2, // ROLL INVERTED ROTATE YAW NEGATIVE
62  MAG_3_HEAD_DOWN = 3, // PITCH POSITIVE pi/2 ROTATE YAW POSITIVE
63  MAG_4_HEAD_UP = 4, // PITCH NEGATIVE pi/2 ROTATE YAW NEGATIVE
64  MAG_5_TURNED_LEFT = 5, // ROLL POSITIVE pi/2 ROTATE YAW POSITIVE
65  MAG_6_TURNED_RIGHT = 6, // ROLL NEGATIVE pi/2 ROTATE YAW NEGATIVE
66  MAG_7_ARDUPILOT = 7, // Random rotations
67  MAG_8_ARDUPILOT = 8, // Random rotations
68  MAG_9_ARDUPILOT = 9, // Random rotations
69 
70  ACC_1_NORMAL = 11, // ROLL OK
71  ACC_2_OVERTURNED = 12, // ROLL INVERTED
72  ACC_3_HEAD_DOWN = 13, // PITCH POSITIVE pi/2
73  ACC_4_HEAD_UP = 14, // PITCH NEGATIVE pi/2
74  ACC_5_TURNED_LEFT = 15, // ROLL POSITIVE pi/2
75  ACC_6_TURNED_RIGHT = 16, // ROLL NEGATIVE pi/2
76 
77  AIRSPEED = 21, // Emulate airspeed
78  };
79  virtual int8_t calibrate(SimMode_t calibrationType) { return -1; }
80 };
81 
82 
83 #endif // UAV_DYNAMICS_SIM_BASE_HPP
virtual void process(double dt_secs, const std::vector< double > &motorSpeedCommandIn, bool isCmdPercent)=0
virtual Eigen::Vector3d getVehicleAngularVelocity(void) const =0
virtual Eigen::Quaterniond getVehicleAttitude() const =0
UavDynamicsSimBase()=default
virtual Eigen::Vector3d getVehiclePosition() const =0
virtual ~UavDynamicsSimBase()=default
virtual int8_t init()=0
Use rosparam here to initialize sim.
virtual void getIMUMeasurement(Eigen::Vector3d &accOutput, Eigen::Vector3d &gyroOutput)=0
virtual bool getMotorsRpm(std::vector< double > &motorsRpm)
virtual void setInitialPosition(const Eigen::Vector3d &position, const Eigen::Quaterniond &attitude)=0
virtual Eigen::Vector3d getVehicleVelocity(void) const =0
virtual int8_t calibrate(SimMode_t calibrationType)


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