From 2a1b03e5d330552183d2ffaa20b083badd56573b Mon Sep 17 00:00:00 2001 From: SimpleMax2407 <62309109+simple-max-2001@users.noreply.github.com> Date: Mon, 14 Oct 2024 21:03:25 +0300 Subject: [PATCH 1/4] First commit --- .gitignore | 1 + AirLib/AirLib.vcxproj | 2 + AirLib/AirLib.vcxproj.filters | 6 + AirLib/include/common/AirSimSettings.hpp | 3 +- .../multirotor/MultiRotorParamsFactory.hpp | 4 + .../firmwares/betaflight/BetaflightApi.hpp | 497 ++++++++++++++++++ .../firmwares/betaflight/BetaflightParams.hpp | 60 +++ Betaflight/BTFL_quadrocopter.txt | 47 ++ PythonClient/airsim/types.py | 29 +- .../Multirotor/SimModeWorldMultiRotor.cpp | 10 +- UnrealPluginFiles.vcxproj | 109 ++-- 11 files changed, 699 insertions(+), 69 deletions(-) create mode 100644 AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp create mode 100644 AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightParams.hpp create mode 100644 Betaflight/BTFL_quadrocopter.txt diff --git a/.gitignore b/.gitignore index feff8336d1..a693ce8c47 100644 --- a/.gitignore +++ b/.gitignore @@ -331,6 +331,7 @@ cmake_build/ /3.3.2.zip /PythonClient/**/cloud.txt /PythonClient/**/cloud.asc +/Unreal/Environments/BlocksV2/BlocksV2.sln /Unreal/Plugins/AirSim/Content/VehicleAdv/SUV/ /suv_download_tmp car_assets.zip diff --git a/AirLib/AirLib.vcxproj b/AirLib/AirLib.vcxproj index 5bc8b7775d..71a5acb3e7 100644 --- a/AirLib/AirLib.vcxproj +++ b/AirLib/AirLib.vcxproj @@ -96,6 +96,8 @@ + + diff --git a/AirLib/AirLib.vcxproj.filters b/AirLib/AirLib.vcxproj.filters index 885766832d..045e337dfd 100644 --- a/AirLib/AirLib.vcxproj.filters +++ b/AirLib/AirLib.vcxproj.filters @@ -456,6 +456,12 @@ Header Files + + Header Files + + + Header Files + diff --git a/AirLib/include/common/AirSimSettings.hpp b/AirLib/include/common/AirSimSettings.hpp index f06701f9a1..3cd501d17e 100644 --- a/AirLib/include/common/AirSimSettings.hpp +++ b/AirLib/include/common/AirSimSettings.hpp @@ -32,6 +32,7 @@ namespace airlib static constexpr char const* kVehicleTypeArduCopterSolo = "arducoptersolo"; static constexpr char const* kVehicleTypeSimpleFlight = "simpleflight"; static constexpr char const* kVehicleTypeArduCopter = "arducopter"; + static constexpr char const* kVehicleTypeBetaflight = "betaflight"; static constexpr char const* kVehicleTypePhysXCar = "physxcar"; static constexpr char const* kVehicleTypeArduRover = "ardurover"; static constexpr char const* kVehicleTypeComputerVision = "computervision"; @@ -817,7 +818,7 @@ namespace airlib auto vehicle_type = Utils::toLower(settings_json.getString("VehicleType", "")); std::unique_ptr vehicle_setting; - if (vehicle_type == kVehicleTypePX4 || vehicle_type == kVehicleTypeArduCopterSolo || vehicle_type == kVehicleTypeArduCopter || vehicle_type == kVehicleTypeArduRover) + if (vehicle_type == kVehicleTypePX4 || vehicle_type == kVehicleTypeArduCopterSolo || vehicle_type == kVehicleTypeArduCopter || vehicle_type == kVehicleTypeBetaflight || vehicle_type == kVehicleTypeArduRover) vehicle_setting = createMavLinkVehicleSetting(settings_json); //for everything else we don't need derived class yet else { diff --git a/AirLib/include/vehicles/multirotor/MultiRotorParamsFactory.hpp b/AirLib/include/vehicles/multirotor/MultiRotorParamsFactory.hpp index 80a840ed07..44916dd4e6 100644 --- a/AirLib/include/vehicles/multirotor/MultiRotorParamsFactory.hpp +++ b/AirLib/include/vehicles/multirotor/MultiRotorParamsFactory.hpp @@ -9,6 +9,7 @@ #include "vehicles/multirotor/firmwares/simple_flight/SimpleFlightQuadXParams.hpp" #include "vehicles/multirotor/firmwares/mavlink/ArduCopterSoloParams.hpp" #include "vehicles/multirotor/firmwares/arducopter/ArduCopterParams.hpp" +#include "vehicles/multirotor/firmwares/betaflight/BetaflightParams.hpp" namespace msr { @@ -33,6 +34,9 @@ namespace airlib else if (vehicle_setting->vehicle_type == AirSimSettings::kVehicleTypeArduCopter) { config.reset(new ArduCopterParams(*static_cast(vehicle_setting), sensor_factory)); } + else if (vehicle_setting->vehicle_type == AirSimSettings::kVehicleTypeBetaflight) { + config.reset(new BetaflightParams(*static_cast(vehicle_setting), sensor_factory)); + } else if (vehicle_setting->vehicle_type == "" || //default config vehicle_setting->vehicle_type == AirSimSettings::kVehicleTypeSimpleFlight) { config.reset(new SimpleFlightQuadXParams(vehicle_setting, sensor_factory)); diff --git a/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp new file mode 100644 index 0000000000..99d4c36185 --- /dev/null +++ b/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp @@ -0,0 +1,497 @@ +#ifndef msr_airlib_BetaflightDroneController_hpp +#define msr_airlib_BetaflightDroneController_hpp + +#include "vehicles/multirotor/api/MultirotorApiBase.hpp" +#include "sensors/SensorCollection.hpp" +#include "physics/Environment.hpp" +#include "physics/Kinematics.hpp" +#include "vehicles/multirotor/MultiRotorParams.hpp" +#include "vehicles/multirotor/MultiRotorPhysicsBody.hpp" +#include "common/Common.hpp" +#include "physics/PhysicsBody.hpp" +#include "common/AirSimSettings.hpp" + +// Sensors +#include "sensors/imu/ImuBase.hpp" +#include "sensors/barometer/BarometerBase.hpp" + +#include "UdpSocket.hpp" + +namespace msr +{ +namespace airlib +{ + + class BetaflightApi : public MultirotorApiBase + { + + public: + BetaflightApi(const MultiRotorParams* vehicle_params, const AirSimSettings::MavLinkConnectionInfo& connection_info) + : connection_info_(connection_info), vehicle_params_(vehicle_params) + { + sensors_ = &getSensors(); + start_time_ = ClockFactory::get()->nowNanos(); + connect(); + } + + ~BetaflightApi() + { + closeConnections(); + } + + public: + virtual void resetImplementation() override + { + MultirotorApiBase::resetImplementation(); + + // Reset state + } + + // Update sensor data & send to betaflight + virtual void update() override + { + MultirotorApiBase::update(); + + // Time + double timestamp = static_cast(ClockFactory::get()->nowNanos() - start_time_) / 1E9; + + if (timestamp >= start_timestamp) { + + if (failed_pkts == 0) sendState(timestamp); + + if (recvControl()) { + + failed_pkts = 0; + } + else { + + failed_pkts++; + + if (failed_pkts >= max_failed_pkts) { + + failed_pkts = 0; + start_timestamp = timestamp + wait_time; + Utils::log(Utils::stringf("Rotors data not recieved. Retry in %.0f sec", wait_time), Utils::kLogLevelWarn); + } + } + } + } + + // necessary overrides + virtual bool isApiControlEnabled() const override + { + return true; + } + virtual void enableApiControl(bool is_enabled) override + { + // Utils::log("Not Implemented: enableApiControl", Utils::kLogLevelInfo); + unused(is_enabled); + } + virtual bool armDisarm(bool arm) override + { + unused(arm); + return true; + } + virtual GeoPoint getHomeGeoPoint() const override + { + return physics_->getEnvironment().getHomeGeoPoint(); + } + virtual void getStatusMessages(std::vector& messages) override + { + unused(messages); + } + + virtual const SensorCollection& getSensors() const override + { + return vehicle_params_->getSensors(); + } + + public: //TODO:MultirotorApiBase implementation + virtual real_T getActuation(unsigned int rotor_index) const override + { + return rotor_controls_[rotor_index]; + } + + virtual size_t getActuatorCount() const override + { + return vehicle_params_->getParams().rotor_count; + } + + virtual void moveByRC(const RCData& rc_data) override + { + unused(rc_data); + // setRCData(rc_data); + } + + virtual void setSimulatedGroundTruth(const Kinematics::State* kinematics, const Environment* environment) override + { + //Utils::log("Not Implemented: setSimulatedGroundTruth", Utils::kLogLevelInfo); + unused(kinematics); + unused(environment); + + if (physics_ == nullptr) { + + for (UpdatableObject* container = this->getParent(); container != nullptr; container = container->getParent()) { + if (container->getName() == "MultiRotorPhysicsBody") { + // cool beans! + // note: cannot use dynamic_cast because Unreal builds with /GR- for some unknown reason... + physics_ = static_cast(container); + break; + } + } + } + } + + virtual bool setRCData(const RCData& rc_data) override + { + last_rcData_ = rc_data; + is_rc_connected_ = true; + + return true; + } + + protected: + virtual Kinematics::State getKinematicsEstimated() const override + { + return physics_->getKinematics(); + } + + virtual Vector3r getPosition() const override + { + return physics_->getKinematics().pose.position; + } + + virtual Vector3r getVelocity() const override + { + return physics_->getKinematics().twist.linear; + } + + virtual Quaternionr getOrientation() const override + { + return physics_->getKinematics().pose.orientation; + } + + virtual LandedState getLandedState() const override + { + return physics_->isGrounded() ? LandedState::Landed : LandedState::Flying; + } + + virtual RCData getRCData() const override + { + //return what we received last time through setRCData + return last_rcData_; + } + + virtual GeoPoint getGpsLocation() const override + { + return physics_->getEnvironment().getState().geo_point; + } + + virtual float getCommandPeriod() const override + { + return 1.0f / 50; //50hz + } + + virtual float getTakeoffZ() const override + { + // pick a number, 3 meters is probably safe + // enough to get out of the backwash turbulence. Negative due to NED coordinate system. + // return params_.takeoff.takeoff_z; + return 3.0; + } + + virtual float getDistanceAccuracy() const override + { + return 0.5f; //measured in simulator by firing commands "MoveToLocation -x 0 -y 0" multiple times and looking at distance traveled + } + + virtual void setControllerGains(uint8_t controllerType, const vector& kp, const vector& ki, const vector& kd) override + { + unused(controllerType); + unused(kp); + unused(ki); + unused(kd); + Utils::log("Not Implemented: setControllerGains", Utils::kLogLevelInfo); + } + + virtual void commandMotorPWMs(float front_right_pwm, float front_left_pwm, float rear_right_pwm, float rear_left_pwm) override + { + unused(front_right_pwm); + unused(front_left_pwm); + unused(rear_right_pwm); + unused(rear_left_pwm); + Utils::log("Not Implemented: commandMotorPWMs", Utils::kLogLevelInfo); + } + + virtual void commandRollPitchYawrateThrottle(float roll, float pitch, float yaw_rate, float throttle) override + { + unused(roll); + unused(pitch); + unused(yaw_rate); + unused(throttle); + Utils::log("Not Implemented: commandRollPitchYawrateThrottle", Utils::kLogLevelInfo); + } + + virtual void commandRollPitchYawZ(float roll, float pitch, float yaw, float z) override + { + unused(roll); + unused(pitch); + unused(yaw); + unused(z); + Utils::log("Not Implemented: commandRollPitchYawZ", Utils::kLogLevelInfo); + } + + virtual void commandRollPitchYawThrottle(float roll, float pitch, float yaw, float throttle) override + { + unused(roll); + unused(pitch); + unused(yaw); + unused(throttle); + Utils::log("Not Implemented: commandRollPitchYawThrottle", Utils::kLogLevelInfo); + } + + virtual void commandRollPitchYawrateZ(float roll, float pitch, float yaw_rate, float z) override + { + unused(roll); + unused(pitch); + unused(yaw_rate); + unused(z); + Utils::log("Not Implemented: commandRollPitchYawrateZ", Utils::kLogLevelInfo); + } + + virtual void commandAngleRatesZ(float roll_rate, float pitch_rate, float yaw_rate, float z) override + { + unused(roll_rate); + unused(pitch_rate); + unused(yaw_rate); + unused(z); + Utils::log("Not Implemented: commandAngleRatesZ", Utils::kLogLevelInfo); + } + + virtual void commandAngleRatesThrottle(float roll_rate, float pitch_rate, float yaw_rate, float throttle) override + { + unused(roll_rate); + unused(pitch_rate); + unused(yaw_rate); + unused(throttle); + Utils::log("Not Implemented: commandAngleRatesZ", Utils::kLogLevelInfo); + } + + virtual void commandVelocity(float vx, float vy, float vz, const YawMode& yaw_mode) override + { + unused(vx); + unused(vy); + unused(vz); + unused(yaw_mode); + Utils::log("Not Implemented: commandVelocity", Utils::kLogLevelInfo); + } + + virtual void commandVelocityZ(float vx, float vy, float z, const YawMode& yaw_mode) override + { + unused(vx); + unused(vy); + unused(z); + unused(yaw_mode); + Utils::log("Not Implemented: commandVelocityZ", Utils::kLogLevelInfo); + } + + virtual void commandPosition(float x, float y, float z, const YawMode& yaw_mode) override + { + unused(x); + unused(y); + unused(z); + unused(yaw_mode); + Utils::log("Not Implemented: commandPosition", Utils::kLogLevelInfo); + } + + virtual const MultirotorApiParams& getMultirotorApiParams() const override + { + return safety_params_; + } + + protected: + void closeConnections() + { + if (motor_socket_ != nullptr) + motor_socket_->close(); + + if (servo_socket_ != nullptr) + servo_socket_->close(); + } + + void connect() + { + ip_ = connection_info_.udp_address; + + closeConnections(); + + if (ip_ == "") { + throw std::invalid_argument("UdpIp setting is invalid."); + } + + Utils::log(Utils::stringf("Using UDP port %d, local IP %s, remote IP %s for receiving servo position", servo_port_, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo); + Utils::log(Utils::stringf("Using UDP port %d, local IP %s, remote IP %s for receiving rotor power", motor_port_, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo); + Utils::log(Utils::stringf("Using UDP port %d, local IP %s, remote IP %s for sending sensor data", state_port_, connection_info_.local_host_ip.c_str(), ip_.c_str()), Utils::kLogLevelInfo); + + motor_socket_ = std::make_unique(); + motor_socket_->bind(connection_info_.local_host_ip, motor_port_); + + servo_socket_ = std::make_unique(); + servo_socket_->bind(connection_info_.local_host_ip, servo_port_); + } + + private: + // actual functions + + void sendState(double timestamp) // send fdmPacket to betaflight i.e udp:9002 + { + if (sensors_ == nullptr || motor_socket_ == nullptr) + return; + + FdmPacket pkt = FdmPacket(); + + // IMU + const auto& imu_output = getImuData(""); + + // Baro + const auto& baro_output = getBarometerData(""); + + // Time + pkt.timestamp = timestamp; + + // Angular Velocity + pkt.imu_angular_velocity_rpy[0] = imu_output.angular_velocity[0]; + pkt.imu_angular_velocity_rpy[1] = imu_output.angular_velocity[1]; + pkt.imu_angular_velocity_rpy[2] = imu_output.angular_velocity[2]; + + // Linear Acceleration + pkt.imu_linear_acceleration_xyz[0] = imu_output.linear_acceleration[0]; + pkt.imu_linear_acceleration_xyz[1] = imu_output.linear_acceleration[1]; + pkt.imu_linear_acceleration_xyz[2] = imu_output.linear_acceleration[2]; + + // Orientation Quaternion. In case USE_IMU_CALC is not defined on betaflight side + pkt.imu_orientation_quat[0] = imu_output.orientation.w(); + pkt.imu_orientation_quat[1] = imu_output.orientation.x(); + pkt.imu_orientation_quat[2] = imu_output.orientation.y(); + pkt.imu_orientation_quat[3] = imu_output.orientation.z(); + + // Position + pkt.position_xyz[0] = 0; + pkt.position_xyz[1] = 0; + pkt.position_xyz[2] = 0; + + // Velocity + pkt.velocity_xyz[0] = 0; + pkt.velocity_xyz[1] = 0; + pkt.velocity_xyz[2] = 0; + + // Pressure + pkt.pressure = baro_output.pressure; + + motor_socket_->sendto(&pkt, sizeof(pkt), ip_, state_port_); + } + + bool recvControl() + { + ServoPacket s_pkt; + ServoPacketRaw sr_pkt; + + int s_recv_ret = motor_socket_->recv(&s_pkt, sizeof(s_pkt), 100); + + if (s_recv_ret != sizeof(s_pkt)) { + if (s_recv_ret <= 0) { + Utils::log(Utils::stringf("Error while receiving rotor control data - ErrorNo: %d", s_recv_ret), Utils::kLogLevelInfo); + } + else { + Utils::log(Utils::stringf("Received %d bytes instead of %zu bytes for rotors", s_recv_ret, sizeof(s_pkt)), Utils::kLogLevelInfo); + } + + return false; + } + + for (auto i = 0; i < kBetaflightMotorCount; ++i) { + rotor_controls_[i] = s_pkt.pwm[i]; + } + + int sr_recv_ret = servo_socket_->recv(&sr_pkt, sizeof(sr_pkt), 100); + + if (sr_recv_ret != sizeof(sr_pkt)) { + if (sr_recv_ret <= 0) { + Utils::log(Utils::stringf("Error while receiving servo control data - ErrorNo: %d", sr_recv_ret), Utils::kLogLevelInfo); + } + else { + Utils::log(Utils::stringf("Received %d bytes instead of %zu bytes for servos", sr_recv_ret, sizeof(sr_pkt)), Utils::kLogLevelInfo); + } + } + else { + + for (auto i = 0; i < kBetaflightServoCount; ++i) { + servo_controls_[i] = sr_pkt.pwm[i]; + } + } + + // Utils::log(Utils::stringf("pwm received: [ %f, %f, %f, %f ]", rotor_controls_[0], rotor_controls_[1], rotor_controls_[2], rotor_controls_[3]), Utils::kLogLevelInfo); + return true; + } + + private: + struct FdmPacket // equivalent of fdm_packet in betaflight SITL + { + double timestamp; // in seconds + double imu_angular_velocity_rpy[3]; // rad/s -> range: +/- 8192; +/- 2000 deg/se + double imu_linear_acceleration_xyz[3]; // m/s/s NED, body frame -> sim 1G = 9.80665, FC 1G = 256 + double imu_orientation_quat[4]; //w, x, y, z + double velocity_xyz[3]; // m/s, earth frame + double position_xyz[3]; // meters, NED from origin + double pressure; // pascals, atmosphere pressure + }; + + static const int kBetaflightMotorCount = 4; + static const int kBetaflightServoCount = 8; + + static const int kBetaflightMaxRCCount = 16; + + struct ServoPacket // equivalent of servo_packet in betaflight SITL + { + uint16_t pwm[kBetaflightMotorCount]; + }; + + struct ServoPacketRaw // equivalent of servo_packet_raw in betaflight SITL + { + uint16_t motorCount; // Count of motor in the PWM output. + float pwm[kBetaflightServoCount]; // Raw PWM from 1100 to 1900 + }; + + float rotor_controls_[kBetaflightMotorCount]; + float servo_controls_[kBetaflightServoCount]; + + // Sockets + std::unique_ptr motor_socket_; + std::unique_ptr servo_socket_; + + const uint16_t servo_port_ = 9001; + const uint16_t motor_port_ = 9002; + const uint16_t state_port_ = 9003; + const uint16_t rc_port_ = 9004; + + MultirotorApiParams safety_params_; + AirSimSettings::MavLinkConnectionInfo connection_info_; + const MultiRotorParams* vehicle_params_; + MultiRotorPhysicsBody* physics_; + const SensorCollection* sensors_; + + std::string ip_; + RCData last_rcData_; + bool is_rc_connected_; + uint64_t start_time_; // changed in contructor call + + uint8_t failed_pkts = 0; + const uint8_t max_failed_pkts = 5; // maximum amount of failed packets + + double start_timestamp = 0; + double wait_time = 5; + }; +} +} // namespace + +#endif \ No newline at end of file diff --git a/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightParams.hpp b/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightParams.hpp new file mode 100644 index 0000000000..73eeed3b9e --- /dev/null +++ b/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightParams.hpp @@ -0,0 +1,60 @@ +// Copyright (c) Microsoft Corporation. All rights reserved. +// Licensed under the MIT License. + +#ifndef msr_airlib_vehicles_BetaflightParams_hpp +#define msr_airlib_vehicles_BetaflightParams_hpp + +#include "vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp" +#include "vehicles/multirotor/MultiRotorParams.hpp" +#include "common/AirSimSettings.hpp" +#include "sensors/SensorFactory.hpp" + +namespace msr +{ +namespace airlib +{ + + class BetaflightParams : public MultiRotorParams + { + public: + BetaflightParams(const AirSimSettings::MavLinkVehicleSetting& vehicle_setting, std::shared_ptr sensor_factory) + : sensor_factory_(sensor_factory) + { + connection_info_ = getConnectionInfo(vehicle_setting); + } + + virtual ~BetaflightParams() = default; + + virtual std::unique_ptr createMultirotorApi() override + { + return std::unique_ptr(new BetaflightApi(this, connection_info_)); + } + + protected: + virtual void setupParams() override + { + auto& params = getParams(); + + // Use connection_info_.model for the model name, see Px4MultiRotorParams for example + + // Only Generic for now + setupFrameGenericQuad(params); + } + + virtual const SensorFactory* getSensorFactory() const override + { + return sensor_factory_.get(); + } + + static const AirSimSettings::MavLinkConnectionInfo& getConnectionInfo(const AirSimSettings::MavLinkVehicleSetting& vehicle_setting) + { + return vehicle_setting.connection_info; + } + + private: + AirSimSettings::MavLinkConnectionInfo connection_info_; + std::shared_ptr sensor_factory_; + }; +} +} //namespace +#endif \ No newline at end of file diff --git a/Betaflight/BTFL_quadrocopter.txt b/Betaflight/BTFL_quadrocopter.txt new file mode 100644 index 0000000000..d8014893ec --- /dev/null +++ b/Betaflight/BTFL_quadrocopter.txt @@ -0,0 +1,47 @@ + +# start the command batch +batch start + +board_name SITL + +# feature +feature -GPS + +# aux +aux 0 0 0 1700 2100 0 0 +aux 1 1 1 1700 2100 0 0 + +# master +set motor_pwm_protocol = PWM +set pid_process_denom = 16 + +profile 0 + +# profile 0 +set p_pitch = 61 +set i_pitch = 109 +set d_pitch = 59 +set f_pitch = 81 +set p_roll = 58 +set i_roll = 104 +set d_roll = 52 +set f_roll = 78 +set p_yaw = 58 +set i_yaw = 104 +set f_yaw = 78 +set d_min_roll = 39 +set d_min_pitch = 44 +set simplified_master_multiplier = 130 +set simplified_feedforward_gain = 50 + +rateprofile 0 + +# rateprofile 0 +set roll_srate = 33 +set pitch_srate = 33 +set yaw_srate = 33 + +# end the command batch +batch end + +save \ No newline at end of file diff --git a/PythonClient/airsim/types.py b/PythonClient/airsim/types.py index 961bceb244..398e022862 100644 --- a/PythonClient/airsim/types.py +++ b/PythonClient/airsim/types.py @@ -31,7 +31,9 @@ def from_msgpack(cls, encoded): for index, (attr_name, attr_type) in enumerate(cls.attribute_order): value = encoded[index] - if issubclass(attr_type, MsgpackMixin): + if isinstance(value, list) and value and isinstance(value[0], MsgpackMixin): + value = [v.from_msgpack() for v in value] + elif issubclass(attr_type, MsgpackMixin): value = attr_type.from_msgpack(value) setattr(obj, attr_name, value) @@ -555,7 +557,6 @@ class CarState(MsgpackMixin): rpm = 0.0 maxrpm = 0.0 handbrake = False - collision = CollisionInfo() kinematics_estimated = KinematicsState() timestamp = np.uint64(0) @@ -565,7 +566,6 @@ class CarState(MsgpackMixin): ('rpm', float), ('maxrpm', float), ('handbrake', bool), - ('collision', CollisionInfo), ('kinematics_estimated', KinematicsState), ('timestamp', np.uint64) ] @@ -588,20 +588,29 @@ class MultirotorState(MsgpackMixin): ('gps_location', GeoPoint), ('timestamp', np.uint64), ('landed_state', int), - ('rc_data', RCData), - ('ready', bool), - ('ready_message', str), - ('can_arm', bool) + ('rc_data', RCData) + ] + + +class RotorParameters(MsgpackMixin): + thrust = 0.0 + torque_scaler = 0.0 + speed = 0.0 + + attribute_order = [ + ('thrust', float), + ('torque_scaler', float), + ('speed', float) ] class RotorStates(MsgpackMixin): timestamp = np.uint64(0) - rotors = [] + rotors: list[RotorParameters] = [] attribute_order = [ - ('timestamp', np.uint64), - ('rotors', list) + ('rotors', list[RotorParameters]), + ('timestamp', np.uint64) ] diff --git a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/SimModeWorldMultiRotor.cpp b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/SimModeWorldMultiRotor.cpp index 86cf0317ad..d737dc26be 100644 --- a/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/SimModeWorldMultiRotor.cpp +++ b/Unreal/Plugins/AirSim/Source/Vehicles/Multirotor/SimModeWorldMultiRotor.cpp @@ -94,10 +94,12 @@ void ASimModeWorldMultiRotor::getExistingVehiclePawns(TArray& pawns) co bool ASimModeWorldMultiRotor::isVehicleTypeSupported(const std::string& vehicle_type) const { - return ((vehicle_type == AirSimSettings::kVehicleTypeSimpleFlight) || - (vehicle_type == AirSimSettings::kVehicleTypePX4) || - (vehicle_type == AirSimSettings::kVehicleTypeArduCopterSolo) || - (vehicle_type == AirSimSettings::kVehicleTypeArduCopter)); + return ((vehicle_type == AirSimSettings::kVehicleTypeSimpleFlight) + || (vehicle_type == AirSimSettings::kVehicleTypePX4) + || (vehicle_type == AirSimSettings::kVehicleTypeArduCopterSolo) + || (vehicle_type == AirSimSettings::kVehicleTypeBetaflight) + || (vehicle_type == AirSimSettings::kVehicleTypeArduCopter) + ); } std::string ASimModeWorldMultiRotor::getVehiclePawnPathName(const AirSimSettings::VehicleSetting& vehicle_setting) const diff --git a/UnrealPluginFiles.vcxproj b/UnrealPluginFiles.vcxproj index af6646ccdb..9c9f3f2d68 100644 --- a/UnrealPluginFiles.vcxproj +++ b/UnrealPluginFiles.vcxproj @@ -98,73 +98,74 @@ - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - - + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + - - - + + + + + + + + - From f063a35fb8376b5aa057cb5e79a232afed7b749d Mon Sep 17 00:00:00 2001 From: SimpleMax2407 <62309109+simple-max-2001@users.noreply.github.com> Date: Thu, 17 Oct 2024 12:10:49 +0300 Subject: [PATCH 2/4] Added rotors reset --- .../firmwares/betaflight/BetaflightApi.hpp | 56 +++++++++---------- 1 file changed, 28 insertions(+), 28 deletions(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp index 99d4c36185..7775394412 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp @@ -31,6 +31,7 @@ namespace airlib { sensors_ = &getSensors(); start_time_ = ClockFactory::get()->nowNanos(); + resetRotors(); connect(); } @@ -71,6 +72,7 @@ namespace airlib failed_pkts = 0; start_timestamp = timestamp + wait_time; + resetRotors(); Utils::log(Utils::stringf("Rotors data not recieved. Retry in %.0f sec", wait_time), Utils::kLogLevelWarn); } } @@ -130,15 +132,7 @@ namespace airlib unused(environment); if (physics_ == nullptr) { - - for (UpdatableObject* container = this->getParent(); container != nullptr; container = container->getParent()) { - if (container->getName() == "MultiRotorPhysicsBody") { - // cool beans! - // note: cannot use dynamic_cast because Unreal builds with /GR- for some unknown reason... - physics_ = static_cast(container); - break; - } - } + physics_ = static_cast(this->getParent()); } } @@ -336,8 +330,14 @@ namespace airlib motor_socket_ = std::make_unique(); motor_socket_->bind(connection_info_.local_host_ip, motor_port_); - servo_socket_ = std::make_unique(); - servo_socket_->bind(connection_info_.local_host_ip, servo_port_); + // servo_socket_ = std::make_unique(); + // servo_socket_->bind(connection_info_.local_host_ip, servo_port_); + } + + void resetRotors() + { + for (auto i = 0; i < kBetaflightMotorCount; i++) + rotor_controls_[i] = 0; } private: @@ -394,8 +394,6 @@ namespace airlib bool recvControl() { ServoPacket s_pkt; - ServoPacketRaw sr_pkt; - int s_recv_ret = motor_socket_->recv(&s_pkt, sizeof(s_pkt), 100); if (s_recv_ret != sizeof(s_pkt)) { @@ -413,22 +411,23 @@ namespace airlib rotor_controls_[i] = s_pkt.pwm[i]; } - int sr_recv_ret = servo_socket_->recv(&sr_pkt, sizeof(sr_pkt), 100); + // ServoPacketRaw sr_pkt; + // int sr_recv_ret = servo_socket_->recv(&sr_pkt, sizeof(sr_pkt), 100); - if (sr_recv_ret != sizeof(sr_pkt)) { - if (sr_recv_ret <= 0) { - Utils::log(Utils::stringf("Error while receiving servo control data - ErrorNo: %d", sr_recv_ret), Utils::kLogLevelInfo); - } - else { - Utils::log(Utils::stringf("Received %d bytes instead of %zu bytes for servos", sr_recv_ret, sizeof(sr_pkt)), Utils::kLogLevelInfo); - } - } - else { + // if (sr_recv_ret != sizeof(sr_pkt)) { + // if (sr_recv_ret <= 0) { + // Utils::log(Utils::stringf("Error while receiving servo control data - ErrorNo: %d", sr_recv_ret), Utils::kLogLevelInfo); + // } + // else { + // Utils::log(Utils::stringf("Received %d bytes instead of %zu bytes for servos", sr_recv_ret, sizeof(sr_pkt)), Utils::kLogLevelInfo); + // } + // } + // else { - for (auto i = 0; i < kBetaflightServoCount; ++i) { - servo_controls_[i] = sr_pkt.pwm[i]; - } - } + // for (auto i = 0; i < kBetaflightServoCount; ++i) { + // servo_controls_[i] = sr_pkt.pwm[i]; + // } + // } // Utils::log(Utils::stringf("pwm received: [ %f, %f, %f, %f ]", rotor_controls_[0], rotor_controls_[1], rotor_controls_[2], rotor_controls_[3]), Utils::kLogLevelInfo); return true; @@ -453,7 +452,7 @@ namespace airlib struct ServoPacket // equivalent of servo_packet in betaflight SITL { - uint16_t pwm[kBetaflightMotorCount]; + float pwm[kBetaflightMotorCount]; }; struct ServoPacketRaw // equivalent of servo_packet_raw in betaflight SITL @@ -482,6 +481,7 @@ namespace airlib std::string ip_; RCData last_rcData_; + bool is_connected_ = false; bool is_rc_connected_; uint64_t start_time_; // changed in contructor call From 3fcfa81b3f654294a812431ae3a5a3824f189e12 Mon Sep 17 00:00:00 2001 From: Simple Max <62309109+simple-max-2001@users.noreply.github.com> Date: Thu, 17 Oct 2024 16:20:48 +0300 Subject: [PATCH 3/4] Compatible with UE 5.2.1 --- .../Blueprints/BP_CameraDirector.uasset | Bin 14500 -> 21714 bytes .../Plugins/AirSim/Source/AirBlueprintLib.cpp | 2 +- Unreal/Plugins/AirSim/Source/AirSim.Build.cs | 7 ++++++- setup.sh | 10 ++++++++-- 4 files changed, 15 insertions(+), 4 deletions(-) diff --git a/Unreal/Plugins/AirSim/Content/Blueprints/BP_CameraDirector.uasset b/Unreal/Plugins/AirSim/Content/Blueprints/BP_CameraDirector.uasset index bf8771b88151fd852af90003b16ab0e76bfd31d7..577097c4b9db2a23a63a479753e10b327e60c692 100644 GIT binary patch literal 21714 zcmeHP33yahmcE6c5XG%gQ4}8_vL~q|1QJn5QrRGcKo&uSq*C=NDXCNyRj+{1iikAr zZfo1xp90-7+S&pxpF6JDZtcvtJJaLZi%pM?Ot-C~HX?KW`|hdtl6t9B2<`aUee0{b z@11+@x#ygF&bdq7_jX=9aq}1Z_wR2xM2M^bLVQd)QWkw@>|8o+Z`J#U{$;(mf6elV zrw=69f+cS*s;bUAcGaR)4_*GjL(#zm+c5l;mi6=e+unWc_&fgNxetfd6YQclE(mTd znYZhs`LpjB|G{k-4YJ#^lsr#`smrEObg z?<+*RGmWoaTI;#H?7d;v{5Y7`Gl`g&MHx+XqJMH#u$FA=@!T;U_g6(d<`~43} zulw}yH{DxG9;wJ4Pq231;6E*_8M7=pqGzqj^*nP=SDe9tv=Ui|Nq7w-F)wkyX!3R<88Mh1xiRDae}SGbO)yGfH8 z%co9SpoesCT%R&EJ5QDiv3<|F9?GebOaq^PlUf#{@OU9MH<&Q~B?H(GEiE9x7F$`y zTFWo0UJr&#Vli)LT`UsSV@9W_zWWbB(u8O&356mnJ;byTjD*GhkB|Hxu+mx<>FChI zMroq8HKf-C!(rVomS>NxAr8A0HU;BB!V&XNn=xYqN^A5sudlOK*ZmEVx%0|uEEe?Z6^XD<3V!sS zA1y{ns?}|d)xHCRNhxVA6PJ84=tPvYk`fZ$P;j+QdW%NFq&czmhlOtrp|Ucsp|?e1 zo#OK~*F6J{7*I>rEv_nDc*M~*V0|QJ1jB7&*fAqtgafO75HFng=+Dq!N&00WZ#*vC zU+-xI+evVP-VqH^i{kY=Mn827m3Z`kHxV)_W8P?cZN#sO`+mP`g{`38r-$_gk%%E4 zy<+nq^u4N)EReN|>mK_fr16ubw1NKTdvClN(vayG-g?~^3H#&XsfO<#LVhJY!8mcz zDJ5L}lU=3XBUrgVXy|@V#Fv0!Rfhu+@ksO0d%=oXG_UnM^7A^c(Jo#r`Po_!FAsak zwEXo3THHCd_MO8duq_zY#e*)-E{I+Z{<w)7D~Ll)s!Z(q^3=PacnKpb)?<3ur;FRR{BG+Y0_&@EpE&=+uTDZV3xpzG zLk#QO^lz}o3fv`W@4fBaeW1e@C#lDUXTtb1Aq9i27H&P~tK(3ilKLk`^83vm-!OP# z10u1kFa2lBx_?~(R^&}t-QU{LiR?p7-dGS4%dR+cf7U+8M}jW5nQ3m9*&N_+zUD&n&f5OUkA?yf9O#*{Fc+2KY`%^CMA4j+rX_1sEfoGiCD#M z9oh#*Ts-{sO(AHbmb_4WddM?FVKNbET0)<5!+xk#SsKT}lDF>t5Ms_V+Vxn89BQ8U zXz^Z&nJ}UW1L08`{Sh74&OL=N>%6{Y-Zs4^;)BzZRFN{7GDNLF)@3 ztqK}~zGY(0{I6bw^6R}TbbnJ&UpX%ji0g(p|M`zRN%%RDNJmLWBtf0keEgNahED2z z?Rtk-?0@9)m0*TO-)M-m9*!Hagp7&xzF06y<~(VE236EY0*1{+FTDA!n_-9b7_Qq& zVjbd;Q0sIsS8v3UJ$lB@*lDt|B$@>0ij7~P_Z#$8mL)!2Y&-}ZQ7=$XzvtDph<^}$UQM|d?Y23Q>iCK?9v?Nkjil>y^v3;afoE!<7E6Zz}n@Sc`mz36&i#yk> zuR<4<`^`u>Fmm4#Gn&hL)4rPLvMLyz>RWE5wE=DIGDe>PgdJB z`4(MTB*wkuuqmpB`f(Fw-X{1!Ps-Cu?9{YKMjBK9gB>wu5~X_bf>^E2ud)yURod?c37= zb+bt2f1!Eox$1hl4Y5I8pJT)0I_dEKO!S&Fpa(o}hIp+R;QcSr^JR$V&j4>X(QC>O z@9Yfm7G{XIG()_$4Ds4C#H+{3=h^6QSJ&sCr7n8OocRCB z#y?`Vm%fk#{LfJRJ7Ff>WRNnYk3IqYS!j@wUTWsO{bouZY=eG{qJJwpaxV=y(cf#+ z4`zLcy{w-f;eyh~v(3D>Unly1v(ZQWfFc4Ny^iS;rHg9J9KUE%HERLYl@t9>ZS+BN ziNb~LPgK{99B|ZqPni?_Pi*wzyY2L4{p?bNF6;;WzuM@7e{?0&XaChX5UTci%AENB z*hU|AQ>7|TpiMl?%aE>epwE54Iq;n5!vvuhe>-Kd$W(eGkmcPOl_iL zfgTM7eb_Qm3+^Ck7xs`V$Uv-a^XPH8#K$Hol2kRD98d0LN!Mz&%{`RDBP8z?A#Yn; zI+Qzadcibz?sQpJ9mjf2?&QKz8)6AvdRIlTR4(K$qou(i-`P=sGD;u4w=wKSeY=-W=vIMpzzy2O0CixM873BnBsqt{aG z@gEEx4pnrTgimpm3Sm9;S6-$(k8}{G)?5_dOerkLKn1bdI#NMuNHd14mkoN zOq5*W6opYm`fDXU21U8VT~0mFDpm`o-a_NaN~#qhEnB!&KRA~TO5y0hdV8p%Q%)Qh z#6PTJx$N&Kapa;g!qi1i<*X}9Gl#1hsg~xV(Tp`4waMB@b`~YAz{-{r#$bgtfpi2e z0yIl-(P(4VwOTqbiJ1;)>r!fqwjIV?n60`fDp)OZS&hh-Jc5o>kF_Lw*+tRZq-6Ey zC~>~1ByWt6-XS|=Wvf_2*z8SgYdzt*XjEq|T@<&>>n2f0-m{E219fNHgGaL#OC?^E zEZ_`LFKY#eCs<|~ecS0eLNUR#T^B_wvlXW@))VJe8-0sJ+=fTCYLI=hcC7ZD%CZ!1 z$Ee)Wr2UGuYVSk4FIsK%R}SWft*eUq{5-Nf7tL@?EvA-m6izS0XjOl@C?!j*6ve_L zibNib3B}aoWnwDb7YH|%PNS7~A>|&rno1>w5@RaimJ+7r=lzwH`L@SGtJl((a*w2! z`B)`$1!>TVm-hBr1p3q^j#8NYm5C!p71`lx8Og1PVTW;aOV9raiYtqENOB(eD10x+ zHX5{0?@SY&gwGWFD+z1F;<|y_T}^TYX!HuuwWYOmINS%!m));8YFRdAm(Oa?MYCVi z`ui&tTb0GJhjiH?^=U-f!rq>{s))C(ck_^A2Nag_Xjq$aW?lFrv@gQ-| z(G)GT5%m?+PC}e5b&eH)i&l`Pj(Wy8Nnx0Hw3c`A)rf<{CC@KSZF-az+NrnW)RR^W z>8bo=#RqHGITGJhD28B-8>iT1N#hb@GUA%oO;Ov*#3fEsb=g-A)CVmdt#yyJKCpbjzAmztkIhI1 z9xrp{dY{+JxuoleS|tT&1hVVqbVc{O?khZ>vt;kSl5C_=)GtD$4~{4nWL!qtXKS5C z)>}!RGO~Gm3dp`osSlB&}_g* z`Y`7lsiSRA<&za3>G|jNQXBCem2J4hl!GJz?+J9@3qe1mE6Yx4pJzWk@8EGfuvTi$ zyC^NBNmzqHu`y1XwRUr`D&+{_qO;Uy1jr1V*Bt3}&8voSI}{!{9%1|{C66s7?=6!aT|{MtbO#9hx{}7QV)E+(y3Qx> zcG115%k*;aT-xeE`&u-IXxrz;)_NPe2l({Y-*{z;-U-u8z}(G*)?lycOTSMeb1r?0 z#bWx$bTVDJ)g4OmDOSX}hY$H!e(Ur@*WP8}hGU?? zjkS;2YJtr{dW#nDWi#Sh@s}Y5DkgP}Sp~`X#PNjVqf;C%NLn1*OhGc1S+Su&Mz!9p zra;Cy6OT3Ew$bA@+(|rpEM`7?ip5qrOJ?kdGR4KhV+j>hFsm zR*b)@H2dkSZR781JvQ%c?loYhbtgNb{am!YiGhRHi!aG(@$3r{+dQuA^K-1qQ_8wi!@6i=&g$Hnw~GAR62I79vgv+S7|5_m!0~hUz3@oOgG;<^-Ezwk?0z!b>Q|6+p45um5jxwOE#{yN+DeIFA-;nRjQjD@ZJ^N0f!c3Vk zy-WrF;Er{|i0HtjRj*(FlYbv^@r>%0A*@ZPj6(^|uaAtqy`pN)ACCI$`QNUqz4(h$ zoM8QMtXXKUkEu^a34X7-vEkXjRSycS@UPnV@Ph0rC)l^yvB2*eyS!(utK4)+(anQ) zj4glq5+~RhHbo|b1H4i`jjqW@g|p*busJS24?Vk?G?f2wwDgry(fFbZMXeC=T}a!Z*%+rztaZHzh!Y{ zvwr!S*&DPc-ETX=@H7vnWc(OM5cy&jO}&{VOTLUm8y}~4HH7pjQF@~iy|yP3rhj>7 zs@h|jO84AuCEd&T9@Ev_>|D9Mft*vHx^29w#S_g6b$^iO@%*GG%hl)k?F~sL;&Z?g&7<-$4yb9cxG zIgqfdr}uj3@}|cEm^%`Z?1Fx z|2hV4AY(f_GWM-3M>h8p(2KE7EdU>!tOWy_L9Zv0CLPyw^F>~EkA{oM7Z~-uM=`#b zJ(_XLRKpBdn1drFgBOdmo`5709FC0NdJU3hJ|sC=T0KQ8pEO~5)ziwb=Hs`$!N>iY zKcd`%>^%{c-lUnGhW|daL|pfie`{s*7AQkc{?C)#Z$ZA)rGgEYw}s`2nBQc~mS0t^=^1(@GB7GT72ECBFK`XY^@Z?CU{#O^E-g1SAqQnp&~ zpA=HcCLx~u=f6%;3b8ObTGpfY7^!@$%FVxUFdlY)fe!@dm-*BwY@P)%wMk5+dw%vU zTGP5Ye}4C}-KDooe$`hrSs|osVB*nhB>T9I7ZD+)2yz4g?TGekRM<&xC%s|Mt!uN- dc={Dg4ES#olp(Encl!K+FFY{;zKR6={{v7De$M~^ literal 14500 zcmeHOdz4hgnXks-DJT%$iZ&o`m`BeH%nYJ*Pj}CQc|RE<4tKim%rx|i?%Ojos|1yx zE+)GevgRBUO-ML;L~=+VO4eW?C!Wo^XXAs!O>ou3C|Oud)TnU-I{W?VR^5Ahrl)CP z{@HW3bh_$(-&fzOzWSpKI7ob_klX{>%?$x}~1+fT6hzi#>Fv-OJ}_l}*n z|HZqHDJux}mg6@^Ce`16iCq>{jjK3%lG$%HNo_?`v`U+?fjr=DPji z-*{_J-1PX9Q+Fq4`rjxd*t@+)-a6;n|KZhV3Jy4*@#ZceSg&u~A2-x2*c!dAboaj7 z7tNSNuz{6~fk&P*5Ni&E@?61$8jS_QT0GCy&{?j8)R^K9#8jUai4j>2+eE((auEH` z9wm+DQSEVg^7BgzONtzBhsRx7RDZ*Hu`|Y(#X9h$mA0+iMt`PW3)= z?d)lc;~J^%puYtDDR2I8cT4g4+HXY1+>ji@Dt~`}?~>a1uKELSuX=yWC(pkLUf=^o zMw3FL*vqfvjG9VM%a^x$ikCO3K~;&XD~ofBIG(ZgqEBq;@zjZzoL`)QO6<2JKU$*0 zO9*L=~^<7)Yr|gremA71L!Fj?xfw0Q< ztow2mBF_o8*C<_TkUcgt)=8dY&R9%IHpC)PHKrw5)sa605RT4-7HLv_YM@W83P%$f zd;GPnWnkRp3J&G?`r>g#zNJAplqc(3lh+;b4;O`Q5i0XIcrGlW|QAwW+Z<1mC5N zU!KCXB^g!O#3>KHfhcrEB0<9>X;>{vL_dy#`NqwFTk{B^cPDmPbO-NLUSP z?9jcd&Tv*qO*L4Zty_6=Jas5nG_@xZOR~T2-2WV?B%qE0oPBlGhKZ9cz~)Fy3xs>v zv?(|I5_6b@gdpPi**|#{J~f1v2bFl76@2z_EA%zMEovwlB#G=-Pt5-r7`WALB@xuv zT?3I@Fk0fdBBn%p>mq)Y9eeX^p9RtEQ^RUgB%-mOJn+b9M5gFrAb78`h7)gNCb$D} zl9%MR?D+aw7nJb~iHOrpla65MhhWOe8mPA#%V+oX-*e~-An^w@)$fk@60o}}+#O-h zbWXki4Rw?ry$y=i%YNy6bk|rQ^vHeM<~}=`9@XutkKJ+p;v5XRHyBYgV^A(U_WGxA zqc;)uAt<>U;>^8t$y#VG!4!;YObz=~c5vgx>F7{FUWt)k{kq@xjN8zHl*s$@AU$yR zzx6>le<*MGTQ6KE1GP> ztW`r@YK*gZ;Krj*A(V7bgF?D$Z0ETETK+}YsPyP5-c(yj;PXtv;QHn-Wl{+vx zf3E^QU~1@c_Xp#u5x5ve2Ia z3EZIgwkkbpO~i*8LvkZwh>AxQa_v+tc^~|stFQZY)@uj92pgJ}KGokAQ2Xn9Jgk3MQ+O0Jw1pB-OCZXAbbjo!VBbok z+=J=aK(33kISURHBDqnri>0xs_UL8?=`zIlh#mT;oo6tFZG7!?xLIp{a6EX+bwFQn z*|GyoA@G)9Gw(t^JNN1xZcIFhZVks&CFt?96*&)$Lqza3f~|aEK?l5N^k&ma3n$I8 zLIzErr4L6}BHV|h+0Jry-(N=0hO^2kP-0505+*Oi*gtPp*FvHmCR+dYeTXlSnmRkv zF}nY!>rTKpgD92bT;~&qZ!pnDdh4w4)OEHwo2s0y8V~#a&fS$5B#)m@b(Rx3wn@)L z{8^8?&h-v<{M0ulVU~LOXfEosn-1DGAq%W`U@CRWH5odh{|3QLU;eZbehr zTf2^Z4WTSnXLbF%HV76|h{Y@Jn~oVEo{etbTJb%V2PN{hu?(=vS^iE;dTv%~+|55X z<`^V5mp6CvTwZYc<>xr9jDC|%@uuS!h?EyZ8A^s=)Cm|5NVEqz1RGV7%B<@W$gr)l z!h-ai&89Fn&9IjZH}^a9bEU=9Oj(2>-&#E4p+?m2(JriBvy<(1r{N8(e=T6#6UCd}g6rF9?zCPKdV6YVcr2^ep9PlDA0olYWqF z>O=z~_KWtjmyjp>W|H@hg6Lz5ZP2q>z>zz5i*}PkG%itPlDA9r9W2i!;E?wN(SBtF z+3xsRBrVO`vFH zl85+1`N$#UGy2Q%H&Tu-#@U(L;8|AZz&xGO%aSc z)5wEPD6&R7lRW89&{+%mV-qZEEAI2Q;jh$9J6?c?Y^c~K+NaL~Mjp-$+R77pXfN8v z2MFycBcY7$-*qRqw?e(tT z76>@B)y0KCY5f~(+w*$YcO;wo`w9}yLchCUM`J%>$}1{d1wFl<(yg(&)h*s_vG(oD zBXzw!gz{9Yq0-)pmahD*+t&9t_f~G*u(7UW2lzP~>94#Mt-i+gV6xQ_)N1mpo z;;$%8Zpg27y181VEggl`QD0@F!QbgDqK+mO}`t*=;ogybm8{V{c7jE}K_k;h(feh!<@4^)jobE|QF(ui|66ukeK zNXuankQiVCX&wv!g>g4f{H!8<0Hx6Jb3G1eXz6J1(A!Ncqy+g}2={?EsPx1cW>M%y|X=6U2)lkS)BP^?) zd=MsSHcDW+H%*B2xoOumf~JN%qw#(T+6?$vfH;JSla0+46qV$^F7ji5HqxNoMkCP0 zb}-3(GxM^3>J=d`o3!RQq{ogH+)a%xZ?q=~J|5CQBmEH-+xU1#Nh2FA!n!Yp!%JV8 zdR#4f42?7!n=Ekk6j`RNt@IQnuOP~{5rrPtHrjN6E<&0uBj{Ms*OYX57E3^Rb66s)Dr~t6j9qK{p$U#t?8HGIgigHQwQlI(+`(7?vjt2&p(a)FK3`R4(V_* zA7-{{hOnxJ74oP>WNl`H$J|Tf4v+63YB{s6)Gq0D8M~DLm}Fv&brMGs76$XgjTY_eyP&`KXfOatB{0%zR{pNzJ5O z>zp#@*=(VesXHv$LQxl`xXYt)>1I8&{`B#DyP1z-lKOmMgshPxZED^^vUiZQZkpHK z)Hb6b6OGI~nXQ#`$ZDf0&qjN@kr^WyS*FIwh#~G%bEQs?m6;*4C3!;ArF3L+3yn%1 z%{BACl@yEVpyg?yt~5}rpfg9v8#3bIgD~IwAgh@>&%tn+ucZf=O|A+uS|vvty~ydf z%iFUe7hrwGe#*=XGD@u2c^3Q}Ayev?er8F{+Gyp#o;bTT@wyT6xztUrC=Gm-?j>6z zqzQJESkcU^bSb*)v$9#nZhp#|oKM+4LhlQZ-A$3|;`;~W7jxHpr6Vf$m5p2qEE@{B zLD+DmvgB%*nj726r~12+x$_#H;>HouMaHUbx0}avH~AXgweA{*!`p=(GG5Zhvh-y) zOVSAXsn5I-(qE26HASO~bjG_6^d1f__ZSj?xfwwE4RV{wrXD^=@mA%hmbu#+4!>Z8 z?3XKro&&ehxM7YUKO%-RWB-oLXZiG3M#qwy*a~VDh$mniygi@x9`iY_NIVyd=T-b! z_B8q2DR`|Gcq^|G(RVmrR@zcQTOf3VcF<4PQ)*XW=vP4dK-dC0sU!A}5(a(rzR*Ia zlQJBJ42L1ZVR*n{$Z!}k9EJ>sAp<*9U50~pqq<+M7Fqc~GITIug@z7=h7N^7hi;~@ zAjP)IEhyyrlo36AE&V-o1PX<=7^6GshzB3V2c1N!gHIb%Nf%%4=jX+21_`Oc z^%LA*QvLi2P&eIoi4$Bu@**tV@>2cAiC3KAGHQW3a^%lkOOBF+c6CON5%#XfWWzl_zo2B|s+N zBsZU5fgCAm!<`>5wpfsPtoVT*PW@62J=y=C6K6Ojb~-QrocKzQT=8W{zl(+mFwBPm z91W+rutw1T^AV3D@$a6%=1-I&Q9C4nYFw3J_?C@tG$>2-ivMz?{NM%1ke=|dlhX=T z)P_7OA-)1~AlS{v0~OAi>S2kIlW-J|VkOSiLHrkUnx_inLKOK893MJStQ~LGL0lrf zQJ_FN?31NT0&rmq#oDP<2k}mzlLbP!jq(ewwUb*=p@X#(u2`Ydx4ReZIY~8R*Y7&H ziZ}H8=AtQ0*mbM4?Q^RJv6rJ7yW_>Olhk+JgZ{0VRNHK*cB@d@I{JJF@G0b`;gA>r zTu4K~RmhaW9ZL|aPvvLQv_5qgIJKAl{jleI4;?Q`KC@<(bQ|X?znKnE5OHj!l(#z| zLK5TaB#JG6i4g-BMii(i?*DNdo?$t+-sEikFi%*PGj2Eg8%@3&@j%5IAy##;Y}3X@ zFH#>oasF@`rV9#oBPig6o6sm|Tce!&^m>kBd`E!h8u5&ZTbg#kT#4PHrO1!$Lv;F- ztimT`lp%wHgBANb_x|eoHTT?|y$<<8ls*u;FRaRPU%)|7cH|U( zOuP5XYk#(<{>W|KvJZa0u{=fL1!>G*Az*{Y$_w~%fwU^l4f-GQvb=y`O^n38>@?UR0u=hV!OGe-WJyGDYcW+yA@~ek-cpe$I^tk`p#PoEq zTR64;!|zv-=DfDq1;)xh$?2Mi|UDJE@!na9MM!e_BZxKT=m-nVS72O4r#}+gn#Xs)xxH+i;Dq;$6i%0K(dV#+ z3r{;n02T_}=23mgf4If(0HDL*JT=)G7o1}XfbTvCJY-fP%VYC}G6adKIfbJbTPtc* zJSXybiwGQidl?A1zLbNUO4jrEqYa1q8YZsreEs&RoBs6u=^x^i2W3dckSkn@nYcQG xGQ<+>7*i-y9te4g{=MNtA0OP6yXNOFVM@s*hnl?fy){{?#_$cO*{ diff --git a/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp b/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp index 7f6f745779..3931456d63 100644 --- a/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp +++ b/Unreal/Plugins/AirSim/Source/AirBlueprintLib.cpp @@ -51,7 +51,7 @@ EAppReturnType::Type UAirBlueprintLib::ShowMessage(EAppMsgType::Type message_typ return FMessageDialog::Open(message_type, FText::FromString(message.c_str()), - title_text); + &title_text); } void UAirBlueprintLib::enableWorldRendering(AActor* context, bool enable) diff --git a/Unreal/Plugins/AirSim/Source/AirSim.Build.cs b/Unreal/Plugins/AirSim/Source/AirSim.Build.cs index de9041afe0..11397360fa 100644 --- a/Unreal/Plugins/AirSim/Source/AirSim.Build.cs +++ b/Unreal/Plugins/AirSim/Source/AirSim.Build.cs @@ -91,8 +91,13 @@ public AirSim(ReadOnlyTargetRules Target) : base(Target) PublicIncludePaths.Add(Path.Combine(AirLibPath, "include")); PublicIncludePaths.Add(Path.Combine(AirLibPath, "deps", "eigen3")); AddOSLibDependencies(Target); + + CompileMode cmplMode = CompileMode.CppCompileWithRpc; + + if (Target.Platform == UnrealTargetPlatform.Linux) + cmplMode = CompileMode.HeaderOnlyWithRpc; - SetupCompileMode(CompileMode.CppCompileWithRpc, Target); + SetupCompileMode(cmplMode, Target); } private void AddOSLibDependencies(ReadOnlyTargetRules Target) diff --git a/setup.sh b/setup.sh index 47cc03e81b..9bb41adf26 100755 --- a/setup.sh +++ b/setup.sh @@ -49,8 +49,7 @@ else #linux rsync \ software-properties-common \ wget \ - libvulkan1 \ - vulkan-utils + libvulkan1 #install clang and build tools VERSION=$(lsb_release -rs | cut -d. -f1) @@ -61,6 +60,13 @@ else #linux sudo apt-get update fi sudo apt-get install -y clang-12 clang++-12 libc++-12-dev libc++abi-12-dev + + + if [ "$VERSION" -gt "20" ]; then + sudo apt-get -y install --no-install-recommends vulkan-tools libunwind-dev + else + sudo apt-get -y install --no-install-recommends vulkan-utils + fi fi if ! which cmake; then From 34cd497d72e8f49557466126d5820a72df2425cc Mon Sep 17 00:00:00 2001 From: Simple Max <62309109+simple-max-2001@users.noreply.github.com> Date: Thu, 17 Oct 2024 17:45:51 +0300 Subject: [PATCH 4/4] Added checking if SITL is connected using armDisarm --- .../firmwares/betaflight/BetaflightApi.hpp | 21 ++++--------------- 1 file changed, 4 insertions(+), 17 deletions(-) diff --git a/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp b/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp index 7775394412..19bf6224ba 100644 --- a/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp +++ b/AirLib/include/vehicles/multirotor/firmwares/betaflight/BetaflightApi.hpp @@ -63,6 +63,7 @@ namespace airlib if (recvControl()) { failed_pkts = 0; + if (!is_connected_) is_connected_ = true; } else { @@ -71,6 +72,7 @@ namespace airlib if (failed_pkts >= max_failed_pkts) { failed_pkts = 0; + is_connected_ = false; start_timestamp = timestamp + wait_time; resetRotors(); Utils::log(Utils::stringf("Rotors data not recieved. Retry in %.0f sec", wait_time), Utils::kLogLevelWarn); @@ -92,7 +94,7 @@ namespace airlib virtual bool armDisarm(bool arm) override { unused(arm); - return true; + return is_connected_; } virtual GeoPoint getHomeGeoPoint() const override { @@ -150,21 +152,6 @@ namespace airlib return physics_->getKinematics(); } - virtual Vector3r getPosition() const override - { - return physics_->getKinematics().pose.position; - } - - virtual Vector3r getVelocity() const override - { - return physics_->getKinematics().twist.linear; - } - - virtual Quaternionr getOrientation() const override - { - return physics_->getKinematics().pose.orientation; - } - virtual LandedState getLandedState() const override { return physics_->isGrounded() ? LandedState::Landed : LandedState::Flying; @@ -476,7 +463,7 @@ namespace airlib MultirotorApiParams safety_params_; AirSimSettings::MavLinkConnectionInfo connection_info_; const MultiRotorParams* vehicle_params_; - MultiRotorPhysicsBody* physics_; + const MultiRotorPhysicsBody* physics_ = nullptr; const SensorCollection* sensors_; std::string ip_;