From 25a628ec8588a85a4c1897ce6418a1104141bed0 Mon Sep 17 00:00:00 2001 From: Ratnesh Madaan Date: Wed, 8 Apr 2020 15:39:47 -0700 Subject: [PATCH] [variable_renames] see full commit msg for details (#2538) multirotor->multirotorphysicsbody, rotor->rotoractuator rotor_info -> rotor actuator info, phys_vehicle->multirotor_physics_body_ --- AirLib/AirLib.vcxproj | 4 +- AirLib/AirLib.vcxproj.filters | 4 +- ...ltiRotor.hpp => MultiRotorPhysicsBody.hpp} | 40 +++++++++---------- .../{Rotor.hpp => RotorActuator.hpp} | 10 ++--- .../vehicles/multirotor/RotorParams.hpp | 1 - .../firmwares/mavlink/ArduCopterSoloApi.hpp | 2 +- AirLibUnitTests/SimpleFlightTest.hpp | 4 +- .../Source/Vehicles/Multirotor/FlyingPawn.cpp | 2 +- .../Source/Vehicles/Multirotor/FlyingPawn.h | 2 +- .../Multirotor/MultirotorPawnEvents.h | 4 +- .../Multirotor/MultirotorPawnSimApi.cpp | 28 ++++++------- .../Multirotor/MultirotorPawnSimApi.h | 10 ++--- 12 files changed, 55 insertions(+), 56 deletions(-) rename AirLib/include/vehicles/multirotor/{MultiRotor.hpp => MultiRotorPhysicsBody.hpp} (82%) rename AirLib/include/vehicles/multirotor/{Rotor.hpp => RotorActuator.hpp} (95%) diff --git a/AirLib/AirLib.vcxproj b/AirLib/AirLib.vcxproj index a4ee1b70a..e0069b3fc 100644 --- a/AirLib/AirLib.vcxproj +++ b/AirLib/AirLib.vcxproj @@ -165,10 +165,10 @@ - + - + diff --git a/AirLib/AirLib.vcxproj.filters b/AirLib/AirLib.vcxproj.filters index 30a87d3c4..02a017018 100644 --- a/AirLib/AirLib.vcxproj.filters +++ b/AirLib/AirLib.vcxproj.filters @@ -213,7 +213,7 @@ Header Files - + Header Files @@ -222,7 +222,7 @@ Header Files - + Header Files diff --git a/AirLib/include/vehicles/multirotor/MultiRotor.hpp b/AirLib/include/vehicles/multirotor/MultiRotorPhysicsBody.hpp similarity index 82% rename from AirLib/include/vehicles/multirotor/MultiRotor.hpp rename to AirLib/include/vehicles/multirotor/MultiRotorPhysicsBody.hpp index 454e6559a..2d69cf5f2 100644 --- a/AirLib/include/vehicles/multirotor/MultiRotor.hpp +++ b/AirLib/include/vehicles/multirotor/MultiRotorPhysicsBody.hpp @@ -1,12 +1,12 @@ // Copyright (c) Microsoft Corporation. All rights reserved. // Licensed under the MIT License. -#ifndef msr_airlib_multirotor_hpp -#define msr_airlib_multirotor_hpp +#ifndef msr_airlib_multirotorphysicsbody_hpp +#define msr_airlib_multirotorphysicsbody_hpp #include "common/Common.hpp" #include "common/CommonStructs.hpp" -#include "Rotor.hpp" +#include "RotorActuator.hpp" #include "api/VehicleApiBase.hpp" #include "api/VehicleSimApiBase.hpp" #include "MultiRotorParams.hpp" @@ -16,9 +16,9 @@ namespace msr { namespace airlib { -class MultiRotor : public PhysicsBody { +class MultiRotorPhysicsBody : public PhysicsBody { public: - MultiRotor(MultiRotorParams* params, VehicleApiBase* vehicle_api, + MultiRotorPhysicsBody(MultiRotorParams* params, VehicleApiBase* vehicle_api, Kinematics* kinematics, Environment* environment) : params_(params), vehicle_api_(vehicle_api) { @@ -101,15 +101,15 @@ class MultiRotor : public PhysicsBody { virtual uint dragVertexCount() const override { - return static_cast(drag_vertices_.size()); + return static_cast(drag_faces_.size()); } virtual PhysicsBodyVertex& getDragVertex(uint index) override { - return drag_vertices_.at(index); + return drag_faces_.at(index); } virtual const PhysicsBodyVertex& getDragVertex(uint index) const override { - return drag_vertices_.at(index); + return drag_faces_.at(index); } virtual real_T getRestitution() const override @@ -121,12 +121,12 @@ class MultiRotor : public PhysicsBody { return params_->getParams().friction; } - Rotor::Output getRotorOutput(uint rotor_index) const + RotorActuator::Output getRotorOutput(uint rotor_index) const { return rotors_.at(rotor_index).getOutput(); } - virtual ~MultiRotor() = default; + virtual ~MultiRotorPhysicsBody() = default; private: //methods void initialize(Kinematics* kinematics, Environment* environment) @@ -139,7 +139,7 @@ class MultiRotor : public PhysicsBody { initSensors(*params_, getKinematics(), getEnvironment()); } - static void createRotors(const MultiRotorParams& params, vector& rotors, const Environment* environment) + static void createRotors(const MultiRotorParams& params, vector& rotors, const Environment* environment) { rotors.clear(); //for each rotor pose @@ -191,13 +191,13 @@ class MultiRotor : public PhysicsBody { * params.linear_drag_coefficient / 2; //add six drag vertices representing 6 sides - drag_vertices_.clear(); - drag_vertices_.emplace_back(Vector3r(0, 0, -params.body_box.z()), Vector3r(0, 0, -1), drag_factor_unit.z()); - drag_vertices_.emplace_back(Vector3r(0, 0, params.body_box.z()), Vector3r(0, 0, 1), drag_factor_unit.z()); - drag_vertices_.emplace_back(Vector3r(0, -params.body_box.y(), 0), Vector3r(0, -1, 0), drag_factor_unit.y()); - drag_vertices_.emplace_back(Vector3r(0, params.body_box.y(), 0), Vector3r(0, 1, 0), drag_factor_unit.y()); - drag_vertices_.emplace_back(Vector3r(-params.body_box.x(), 0, 0), Vector3r(-1, 0, 0), drag_factor_unit.x()); - drag_vertices_.emplace_back(Vector3r( params.body_box.x(), 0, 0), Vector3r( 1, 0, 0), drag_factor_unit.x()); + drag_faces_.clear(); + drag_faces_.emplace_back(Vector3r(0, 0, -params.body_box.z()), Vector3r(0, 0, -1), drag_factor_unit.z()); + drag_faces_.emplace_back(Vector3r(0, 0, params.body_box.z()), Vector3r(0, 0, 1), drag_factor_unit.z()); + drag_faces_.emplace_back(Vector3r(0, -params.body_box.y(), 0), Vector3r(0, -1, 0), drag_factor_unit.y()); + drag_faces_.emplace_back(Vector3r(0, params.body_box.y(), 0), Vector3r(0, 1, 0), drag_factor_unit.y()); + drag_faces_.emplace_back(Vector3r(-params.body_box.x(), 0, 0), Vector3r(-1, 0, 0), drag_factor_unit.x()); + drag_faces_.emplace_back(Vector3r( params.body_box.x(), 0, 0), Vector3r( 1, 0, 0), drag_factor_unit.x()); } @@ -205,8 +205,8 @@ class MultiRotor : public PhysicsBody { MultiRotorParams* params_; //let us be the owner of rotors object - vector rotors_; - vector drag_vertices_; + vector rotors_; + vector drag_faces_; std::unique_ptr environment_; VehicleApiBase* vehicle_api_; diff --git a/AirLib/include/vehicles/multirotor/Rotor.hpp b/AirLib/include/vehicles/multirotor/RotorActuator.hpp similarity index 95% rename from AirLib/include/vehicles/multirotor/Rotor.hpp rename to AirLib/include/vehicles/multirotor/RotorActuator.hpp index bc749cba8..d3398bc9a 100644 --- a/AirLib/include/vehicles/multirotor/Rotor.hpp +++ b/AirLib/include/vehicles/multirotor/RotorActuator.hpp @@ -3,8 +3,8 @@ -#ifndef airsimcore_motor_hpp -#define airsimcore_motor_hpp +#ifndef rotor_actuator_hpp +#define rotor_actuator_hpp #include #include "common/Common.hpp" @@ -18,7 +18,7 @@ namespace msr { namespace airlib { //Rotor gets control signal as input (PWM or voltage represented from 0 to 1) which causes //change in rotation speed and turning direction and ultimately produces force and thrust as //output -class Rotor : public PhysicsBodyVertex { +class RotorActuator : public PhysicsBodyVertex { public: //types struct Output { real_T thrust; @@ -30,11 +30,11 @@ class Rotor : public PhysicsBodyVertex { }; public: //methods - Rotor() + RotorActuator() { //allow default constructor with later call for initialize } - Rotor(const Vector3r& position, const Vector3r& normal, RotorTurningDirection turning_direction, + RotorActuator(const Vector3r& position, const Vector3r& normal, RotorTurningDirection turning_direction, const RotorParams& params, const Environment* environment, uint id = -1) { initialize(position, normal, turning_direction, params, environment, id); diff --git a/AirLib/include/vehicles/multirotor/RotorParams.hpp b/AirLib/include/vehicles/multirotor/RotorParams.hpp index d2bf8bafd..d2e678c54 100644 --- a/AirLib/include/vehicles/multirotor/RotorParams.hpp +++ b/AirLib/include/vehicles/multirotor/RotorParams.hpp @@ -4,7 +4,6 @@ #ifndef msr_airlib_RotorParams_hpp #define msr_airlib_RotorParams_hpp - #include "common/Common.hpp" namespace msr { diff --git a/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp index 90ae572d1..5bf951040 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/mavlink/ArduCopterSoloApi.hpp @@ -2,7 +2,7 @@ #define msr_airlib_ArduCopterSoloApi_h #include "AdHocConnection.hpp" -#include "vehicles/multirotor/MultiRotor.hpp" +#include "vehicles/multirotor/MultiRotorPhysicsBody.hpp" #include "vehicles/multirotor/firmwares/mavlink/MavLinkMultirotorApi.hpp" namespace msr { namespace airlib { diff --git a/AirLibUnitTests/SimpleFlightTest.hpp b/AirLibUnitTests/SimpleFlightTest.hpp index 949c046f8..963b526da 100644 --- a/AirLibUnitTests/SimpleFlightTest.hpp +++ b/AirLibUnitTests/SimpleFlightTest.hpp @@ -8,7 +8,7 @@ #include "physics/FastPhysicsEngine.hpp" #include "vehicles/multirotor/api/MultirotorApiBase.hpp" #include "common/SteppableClock.hpp" -#include "vehicles/multirotor/MultiRotor.hpp" +#include "vehicles/multirotor/MultiRotorPhysicsBody.hpp" namespace msr { namespace airlib { @@ -39,7 +39,7 @@ class SimpleFlightTest : public TestBase initial_environment.geo_point = GeoPoint(); environment.reset(new Environment(initial_environment)); - MultiRotor vehicle(params.get(), api.get(), kinematics.get(), environment.get()); + MultiRotorPhysicsBody vehicle(params.get(), api.get(), kinematics.get(), environment.get()); std::vector vehicles = { &vehicle }; std::unique_ptr physics_engine(new FastPhysicsEngine()); diff --git a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/FlyingPawn.cpp b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/FlyingPawn.cpp index 6d7005591..af4ccb355 100644 --- a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/FlyingPawn.cpp +++ b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/FlyingPawn.cpp @@ -79,7 +79,7 @@ void AFlyingPawn::NotifyHit(class UPrimitiveComponent* MyComp, class AActor* Oth HitNormal, NormalImpulse, Hit); } -void AFlyingPawn::setRotorSpeed(const std::vector& rotor_infos) +void AFlyingPawn::setRotorSpeed(const std::vector& rotor_infos) { for (auto rotor_index = 0; rotor_index < rotor_infos.size(); ++rotor_index) { auto comp = rotating_movements_[rotor_index]; diff --git a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/FlyingPawn.h b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/FlyingPawn.h index ad657e7d5..9cf5db58f 100644 --- a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/FlyingPawn.h +++ b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/FlyingPawn.h @@ -34,7 +34,7 @@ class AIRSIM_API AFlyingPawn : public APawn return &pawn_events_; } //called by API to set rotor speed - void setRotorSpeed(const std::vector& rotor_infos); + void setRotorSpeed(const std::vector& rotor_infos); private: //variables diff --git a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnEvents.h b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnEvents.h index 007474f62..611e3b475 100644 --- a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnEvents.h +++ b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnEvents.h @@ -11,14 +11,14 @@ class MultirotorPawnEvents : public PawnEvents { public: //types typedef msr::airlib::real_T real_T; - struct RotorInfo { + struct RotorActuatorInfo { real_T rotor_speed = 0; int rotor_direction = 0; real_T rotor_thrust = 0; real_T rotor_control_filtered = 0; }; - typedef common_utils::Signal&> ActuatorsSignal; + typedef common_utils::Signal&> ActuatorsSignal; public: ActuatorsSignal& getActuatorSignal(); diff --git a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.cpp b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.cpp index 432abc39a..f10dd3fe8 100644 --- a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.cpp @@ -27,10 +27,10 @@ void MultirotorPawnSimApi::initialize() vehicle_params_ = MultiRotorParamsFactory::createConfig(getVehicleSetting(), sensor_factory); vehicle_api_ = vehicle_params_->createMultirotorApi(); //setup physics vehicle - phys_vehicle_ = std::unique_ptr(new MultiRotor(vehicle_params_.get(), vehicle_api_.get(), + multirotor_physics_body_ = std::unique_ptr(new MultiRotorPhysicsBody(vehicle_params_.get(), vehicle_api_.get(), getKinematics(), getEnvironment())); - rotor_count_ = phys_vehicle_->wrenchVertexCount(); - rotor_info_.assign(rotor_count_, RotorInfo()); + rotor_count_ = multirotor_physics_body_->wrenchVertexCount(); + rotor_actuator_info_.assign(rotor_count_, RotorActuatorInfo()); vehicle_api_->setSimulatedGroundTruth(getGroundTruthKinematics(), getGroundTruthEnvironment()); @@ -60,21 +60,21 @@ void MultirotorPawnSimApi::updateRenderedState(float dt) //move collision info from rendering engine to vehicle const CollisionInfo& collision_info = getCollisionInfo(); - phys_vehicle_->setCollisionInfo(collision_info); + multirotor_physics_body_->setCollisionInfo(collision_info); if (pending_pose_status_ == PendingPoseStatus::RenderStatePending) { - phys_vehicle_->setPose(pending_phys_pose_); + multirotor_physics_body_->setPose(pending_phys_pose_); pending_pose_status_ = PendingPoseStatus::RenderPending; } - last_phys_pose_ = phys_vehicle_->getPose(); + last_phys_pose_ = multirotor_physics_body_->getPose(); - collision_response = phys_vehicle_->getCollisionResponseInfo(); + collision_response = multirotor_physics_body_->getCollisionResponseInfo(); //update rotor poses for (unsigned int i = 0; i < rotor_count_; ++i) { - const auto& rotor_output = phys_vehicle_->getRotorOutput(i); - RotorInfo* info = &rotor_info_[i]; + const auto& rotor_output = multirotor_physics_body_->getRotorOutput(i); + RotorActuatorInfo* info = &rotor_actuator_info_[i]; info->rotor_speed = rotor_output.speed; info->rotor_direction = static_cast(rotor_output.turning_direction); info->rotor_thrust = rotor_output.thrust; @@ -126,7 +126,7 @@ void MultirotorPawnSimApi::updateRendering(float dt) UAirBlueprintLib::LogMessage(FString(e.what()), TEXT(""), LogDebugLevel::Failure, 30); } - pawn_events_->getActuatorSignal().emit(rotor_info_); + pawn_events_->getActuatorSignal().emit(rotor_actuator_info_); } void MultirotorPawnSimApi::setPose(const Pose& pose, bool ignore_collision) @@ -142,7 +142,7 @@ void MultirotorPawnSimApi::resetImplementation() PawnSimApi::resetImplementation(); vehicle_api_->reset(); - phys_vehicle_->reset(); + multirotor_physics_body_->reset(); vehicle_api_messages_.clear(); } @@ -153,7 +153,7 @@ void MultirotorPawnSimApi::update() PawnSimApi::update(); //update forces on vertices - phys_vehicle_->update(); + multirotor_physics_body_->update(); //update to controller must be done after kinematics have been updated by physics engine } @@ -162,12 +162,12 @@ void MultirotorPawnSimApi::reportState(StateReporter& reporter) { PawnSimApi::reportState(reporter); - phys_vehicle_->reportState(reporter); + multirotor_physics_body_->reportState(reporter); } MultirotorPawnSimApi::UpdatableObject* MultirotorPawnSimApi::getPhysicsBody() { - return phys_vehicle_->getPhysicsBody(); + return multirotor_physics_body_->getPhysicsBody(); } //*** End: UpdatableState implementation ***// diff --git a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.h b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.h index 6254c5d6c..3e3d17916 100644 --- a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.h +++ b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/MultirotorPawnSimApi.h @@ -3,7 +3,7 @@ #include "CoreMinimal.h" #include "PawnSimApi.h" -#include "vehicles/multirotor/MultiRotor.hpp" +#include "vehicles/multirotor/MultiRotorPhysicsBody.hpp" #include "vehicles/multirotor/MultiRotorParams.hpp" #include "physics//Kinematics.hpp" #include "common/Common.hpp" @@ -18,12 +18,12 @@ class MultirotorPawnSimApi : public PawnSimApi public: typedef msr::airlib::real_T real_T; typedef msr::airlib::Utils Utils; - typedef msr::airlib::MultiRotor MultiRotor; + typedef msr::airlib::MultiRotorPhysicsBody MultiRotor; typedef msr::airlib::StateReporter StateReporter; typedef msr::airlib::UpdatableObject UpdatableObject; typedef msr::airlib::Pose Pose; - typedef MultirotorPawnEvents::RotorInfo RotorInfo; + typedef MultirotorPawnEvents::RotorActuatorInfo RotorActuatorInfo; public: virtual void initialize() override; @@ -60,9 +60,9 @@ class MultirotorPawnSimApi : public PawnSimApi std::unique_ptr vehicle_api_; std::unique_ptr vehicle_params_; - std::unique_ptr phys_vehicle_; + std::unique_ptr multirotor_physics_body_; unsigned int rotor_count_; - std::vector rotor_info_; + std::vector rotor_actuator_info_; //show info on collision response from physics engine CollisionResponse collision_response;