multirotor.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 #ifndef SRC_DYNAMICS_MULTIROTOR_MULTIROTOR_HPP
20 #define SRC_DYNAMICS_MULTIROTOR_MULTIROTOR_HPP
21 
22 #include "uavDynamicsSimBase.hpp"
23 #include "../libs/multicopterDynamicsSim/multicopterDynamicsSim.hpp"
24 
26 public:
27  MultirotorDynamics() = default;
28  ~MultirotorDynamics() = default;
29 
30  int8_t init() override;
31  void setInitialPosition(const Eigen::Vector3d & position,
32  const Eigen::Quaterniond& attitude) override;
33 
34  void process(double dt_secs, const std::vector<double> & setpoint) override;
35 
36  Eigen::Vector3d getVehiclePosition() const override;
37  Eigen::Quaterniond getVehicleAttitude() const override;
38  Eigen::Vector3d getVehicleVelocity(void) const override;
39  Eigen::Vector3d getVehicleAirspeed() const override;
40  Eigen::Vector3d getVehicleAngularVelocity(void) const override;
41  void getIMUMeasurement(Eigen::Vector3d & accOutput, Eigen::Vector3d & gyroOutput) override;
42  bool getMotorsRpm(std::vector<double>& motorsRpm) override;
43 
44 protected:
48  virtual void initStaticMotorTransform(double momentArm) = 0;
49 
53  virtual std::vector<double> mapCmdActuator(std::vector<double> cmd) const = 0;
54 
55  std::unique_ptr<MulticopterDynamicsSim> multicopterSim_;
57 };
58 
59 #endif // SRC_DYNAMICS_MULTIROTOR_MULTIROTOR_HPP
MultirotorDynamics::number_of_motors
uint8_t number_of_motors
Definition: multirotor.hpp:56
MultirotorDynamics::getVehicleAttitude
Eigen::Quaterniond getVehicleAttitude() const override
Definition: multirotor.cpp:128
MultirotorDynamics::getIMUMeasurement
void getIMUMeasurement(Eigen::Vector3d &accOutput, Eigen::Vector3d &gyroOutput) override
Definition: multirotor.cpp:140
MultirotorDynamics::process
void process(double dt_secs, const std::vector< double > &setpoint) override
Definition: multirotor.cpp:120
MultirotorDynamics::getVehicleVelocity
Eigen::Vector3d getVehicleVelocity(void) const override
Definition: multirotor.cpp:131
MultirotorDynamics::getVehiclePosition
Eigen::Vector3d getVehiclePosition() const override
Definition: multirotor.cpp:125
uavDynamicsSimBase.hpp
MultirotorDynamics::getVehicleAirspeed
Eigen::Vector3d getVehicleAirspeed() const override
Definition: multirotor.cpp:134
MultirotorDynamics::mapCmdActuator
virtual std::vector< double > mapCmdActuator(std::vector< double > cmd) const =0
Convert actuator indexes from PX4 notation to internal Flightgoggles notation.
MultirotorDynamics::MultirotorDynamics
MultirotorDynamics()=default
UavDynamicsSimBase
Definition: uavDynamicsSimBase.hpp:30
MultirotorDynamics::getMotorsRpm
bool getMotorsRpm(std::vector< double > &motorsRpm) override
Definition: multirotor.cpp:145
MultirotorDynamics::~MultirotorDynamics
~MultirotorDynamics()=default
MultirotorDynamics
Definition: multirotor.hpp:25
MultirotorDynamics::getVehicleAngularVelocity
Eigen::Vector3d getVehicleAngularVelocity(void) const override
Definition: multirotor.cpp:137
MultirotorDynamics::multicopterSim_
std::unique_ptr< MulticopterDynamicsSim > multicopterSim_
Definition: multirotor.hpp:55
MultirotorDynamics::init
int8_t init() override
Use rosparam here to initialize sim.
Definition: multirotor.cpp:42
MultirotorDynamics::setInitialPosition
void setInitialPosition(const Eigen::Vector3d &position, const Eigen::Quaterniond &attitude) override
Definition: multirotor.cpp:115
MultirotorDynamics::initStaticMotorTransform
virtual void initStaticMotorTransform(double momentArm)=0
Set motor frames.


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