diff --git a/AirLib/include/api/RpcLibAdapatorsBase.hpp b/AirLib/include/api/RpcLibAdapatorsBase.hpp index 50701270c3..96bc16ee49 100644 --- a/AirLib/include/api/RpcLibAdapatorsBase.hpp +++ b/AirLib/include/api/RpcLibAdapatorsBase.hpp @@ -65,7 +65,7 @@ class RpcLibAdapatorsBase { } }; struct RotorVector { - RotorParameters rotor[4]; + std::vector rotor; MSGPACK_DEFINE_MAP(rotor); @@ -74,8 +74,10 @@ class RpcLibAdapatorsBase { RotorVector(const msr::airlib::RotorVector& s) { - for (unsigned int i = 0; i < 5; i++) + rotor.clear(); + for (unsigned int i = 0; i < s.rotor.size(); i++) { + rotor.push_back(RotorParameters()); rotor[i] = s.rotor[i]; } } @@ -83,7 +85,7 @@ class RpcLibAdapatorsBase { msr::airlib::RotorVector to() const { msr::airlib::RotorVector d; - for (unsigned int i = 0; i < 5; i++) + for (unsigned int i = 0; i < d.rotor.size(); i++) { d.rotor[i].speed = rotor[i].speed; d.rotor[i].thrust = rotor[i].thrust; diff --git a/AirLib/include/common/CommonStructs.hpp b/AirLib/include/common/CommonStructs.hpp index 67978a3166..edaef49eaa 100644 --- a/AirLib/include/common/CommonStructs.hpp +++ b/AirLib/include/common/CommonStructs.hpp @@ -18,7 +18,7 @@ struct RotorParameters { {} }; struct RotorVector { - RotorParameters rotor[4]; + std::vector rotor; RotorVector() {} diff --git a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.cpp b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.cpp index 6ff325ba3a..7573acd121 100644 --- a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.cpp @@ -72,9 +72,11 @@ void MultirotorPawnSimApi::updateRenderedState(float dt) collision_response = multirotor_physics_body_->getCollisionResponseInfo(); //update rotor poses + rotor_states_.rotors.rotor.clear(); for (unsigned int i = 0; i < rotor_count_; ++i) { const auto& rotor_output = multirotor_physics_body_->getRotorOutput(i); // update private rotor variable + rotor_states_.rotors.rotor.push_back(RotorParameters()); rotor_states_.rotors.rotor[i].speed = rotor_output.speed; rotor_states_.rotors.rotor[i].thrust = rotor_output.thrust; rotor_states_.rotors.rotor[i].torque_scaler = rotor_output.torque_scaler;