Go to the documentation of this file.
19 #ifndef SRC_DYNAMICS_MULTIROTOR_MULTIROTOR_HPP
20 #define SRC_DYNAMICS_MULTIROTOR_MULTIROTOR_HPP
23 #include "../libs/multicopterDynamicsSim/multicopterDynamicsSim.hpp"
30 int8_t
init()
override;
32 const Eigen::Quaterniond& attitude)
override;
34 void process(
double dt_secs,
const std::vector<double> & setpoint)
override;
41 void getIMUMeasurement(Eigen::Vector3d & accOutput, Eigen::Vector3d & gyroOutput)
override;
42 bool getMotorsRpm(std::vector<double>& motorsRpm)
override;
53 virtual std::vector<double>
mapCmdActuator(std::vector<double> cmd)
const = 0;
59 #endif // SRC_DYNAMICS_MULTIROTOR_MULTIROTOR_HPP
Eigen::Quaterniond getVehicleAttitude() const override
void getIMUMeasurement(Eigen::Vector3d &accOutput, Eigen::Vector3d &gyroOutput) override
void process(double dt_secs, const std::vector< double > &setpoint) override
Eigen::Vector3d getVehicleVelocity(void) const override
Eigen::Vector3d getVehiclePosition() const override
Eigen::Vector3d getVehicleAirspeed() const override
virtual std::vector< double > mapCmdActuator(std::vector< double > cmd) const =0
Convert actuator indexes from PX4 notation to internal Flightgoggles notation.
MultirotorDynamics()=default
bool getMotorsRpm(std::vector< double > &motorsRpm) override
~MultirotorDynamics()=default
Eigen::Vector3d getVehicleAngularVelocity(void) const override
std::unique_ptr< MulticopterDynamicsSim > multicopterSim_
int8_t init() override
Use rosparam here to initialize sim.
void setInitialPosition(const Eigen::Vector3d &position, const Eigen::Quaterniond &attitude) override
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