20 #ifndef MULTICOPTER_DYNAMICS_WRAPPER_BASE_HPP 21 #define MULTICOPTER_DYNAMICS_WRAPPER_BASE_HPP 24 #include "../libs/multicopterDynamicsSim/multicopterDynamicsSim.hpp" 31 int8_t
init()
override;
33 const Eigen::Quaterniond& attitude)
override;
35 void process(
double dt_secs,
const std::vector<double> & motorSpeedCommandIn,
bool isCmdPercent)
override;
41 void getIMUMeasurement(Eigen::Vector3d & accOutput, Eigen::Vector3d & gyroOutput)
override;
56 #endif // MULTICOPTER_DYNAMICS_WRAPPER_BASE_HPP void getIMUMeasurement(Eigen::Vector3d &accOutput, Eigen::Vector3d &gyroOutput) override
~FlightgogglesDynamics() final=default
void initStaticMotorTransform()
std::vector< double > mapCmdActuator(std::vector< double > cmd) const
Convert actuator indexes from PX4 notation to internal Flightgoggles notation.
std::unique_ptr< MulticopterDynamicsSim > multicopterSim_
void process(double dt_secs, const std::vector< double > &motorSpeedCommandIn, bool isCmdPercent) override
Eigen::Vector3d getVehicleVelocity(void) const override
FlightgogglesDynamics()=default
Eigen::Vector3d getVehicleAngularVelocity(void) const override
void setInitialPosition(const Eigen::Vector3d &position, const Eigen::Quaterniond &attitude) override
int8_t init() override
Use rosparam here to initialize sim.
Eigen::Vector3d getVehiclePosition() const override
Eigen::Quaterniond getVehicleAttitude() const override