diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 00000000..02f6ee82 --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,26 @@ +repos: + - repo: https://github.com/pre-commit/pre-commit-hooks + rev: v5.0.0 + hooks: + - id: trailing-whitespace + - id: end-of-file-fixer + - id: check-toml + - id: check-yaml + - id: check-added-large-files + - id: check-case-conflict + - id: check-merge-conflict + - id: detect-private-key + + - repo: https://github.com/astral-sh/ruff-pre-commit + rev: v0.14.11 + hooks: + - id: ruff-check + args: [--fix, --exit-non-zero-on-fix] + - id: ruff-format + + - repo: https://github.com/pre-commit/mirrors-mypy + rev: v1.19.1 + hooks: + - id: mypy + additional_dependencies: [] + args: [--ignore-missing-imports, --strict] diff --git a/AirSim/AirLib/include/api/RpcLibClientBase.hpp b/AirSim/AirLib/include/api/RpcLibClientBase.hpp index d21792a1..ce9e5dae 100644 --- a/AirSim/AirLib/include/api/RpcLibClientBase.hpp +++ b/AirSim/AirLib/include/api/RpcLibClientBase.hpp @@ -63,7 +63,7 @@ class RpcLibClientBase { void simPlotLineStrip(const vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent); void simPlotLineList(const vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent); void simPlotArrows(const vector& points_start, const vector& points_end, const vector& color_rgba, float thickness, float arrow_size, float duration, bool is_persistent); - void simPlotStrings(const vector& strings, const vector& positions, float scale, const vector& color_rgba, float duration); + void simPlotStrings(const vector& strings, const vector& positions, float scale, const vector& color_rgba, float duration); void simPlotTransforms(const vector& poses, float scale, float thickness, float duration, bool is_persistent); void simPlotTransformsWithNames(const vector& poses, const vector& names, float tf_scale, float tf_thickness, float text_scale, const vector& text_color_rgba, float duration); @@ -84,6 +84,8 @@ class RpcLibClientBase { Pose simGetVehiclePose(const std::string& vehicle_name = "") const; void simSetVehiclePose(const Pose& pose, bool ignore_collision, const std::string& vehicle_name = ""); + void simResetToPose(const Pose& pose, const std::string& vehicle_name = ""); + void simSetVehicleLinearVelocity(const Vector3r& velocity, const std::string& vehicle_name = ""); void simSetTraceLine(const std::vector& color_rgba, float thickness=3.0f, const std::string& vehicle_name = ""); vector simGetImages(vector request, const std::string& vehicle_name = ""); diff --git a/AirSim/AirLib/include/api/VehicleSimApiBase.hpp b/AirSim/AirLib/include/api/VehicleSimApiBase.hpp index 9a626201..648d8112 100644 --- a/AirSim/AirLib/include/api/VehicleSimApiBase.hpp +++ b/AirSim/AirLib/include/api/VehicleSimApiBase.hpp @@ -23,7 +23,7 @@ class VehicleSimApiBase : public msr::airlib::UpdatableObject { } //this method is called at every render tick when we want to transfer state from - //physics engine to render engine. As physics engine is halted while + //physics engine to render engine. As physics engine is halted while //this happens, this method should do minimal processing virtual void updateRenderedState(float dt) { @@ -50,6 +50,8 @@ class VehicleSimApiBase : public msr::airlib::UpdatableObject { virtual Pose getPose() const = 0; virtual void setPose(const Pose& pose, bool ignore_collision) = 0; + virtual void resetToPose(const Pose& pose) = 0; + virtual void setLinearVelocity(const Vector3r& velocity) = 0; virtual const Kinematics::State* getGroundTruthKinematics() const = 0; virtual const WheelStates* getWheelStates() const = 0; diff --git a/AirSim/AirLib/include/api/WorldSimApiBase.hpp b/AirSim/AirLib/include/api/WorldSimApiBase.hpp index ba463b05..a917f2a2 100644 --- a/AirSim/AirLib/include/api/WorldSimApiBase.hpp +++ b/AirSim/AirLib/include/api/WorldSimApiBase.hpp @@ -28,6 +28,7 @@ class WorldSimApiBase { virtual bool isPaused() const = 0; virtual void reset() = 0; + virtual void resetToPose(const Pose& pose, const std::string& vehicle_name = "") = 0; virtual void pause(bool is_paused) = 0; virtual void continueForTime(double seconds) = 0; @@ -45,12 +46,12 @@ class WorldSimApiBase { //----------- Plotting APIs ----------/ virtual void simFlushPersistentMarkers() = 0; - virtual void simPlotPoints(const vector& points, const vector& color_rgba, float size, float duration, bool is_persistent) = 0; - virtual void simPlotLineStrip(const vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent) = 0; - virtual void simPlotLineList(const vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent) = 0; - virtual void simPlotArrows(const vector& points_start, const vector& points_end, const vector& color_rgba, float thickness, float arrow_size, float duration, bool is_persistent) = 0; + virtual void simPlotPoints(const vector& points, const vector& color_rgba, float size, float duration, bool is_persistent) = 0; + virtual void simPlotLineStrip(const vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent) = 0; + virtual void simPlotLineList(const vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent) = 0; + virtual void simPlotArrows(const vector& points_start, const vector& points_end, const vector& color_rgba, float thickness, float arrow_size, float duration, bool is_persistent) = 0; virtual void simPlotStrings(const vector& strings, const vector& positions, float scale, const vector& color_rgba, float duration) = 0; - virtual void simPlotTransforms(const vector& poses, float scale, float thickness, float duration, bool is_persistent) = 0; + virtual void simPlotTransforms(const vector& poses, float scale, float thickness, float duration, bool is_persistent) = 0; virtual void simPlotTransformsWithNames(const vector& poses, const vector& names, float tf_scale, float tf_thickness, float text_scale, const vector& text_color_rgba, float duration) = 0; virtual std::vector listSceneObjects(const std::string& name_regex) const = 0; diff --git a/AirSim/AirLib/src/api/RpcLibClientBase.cpp b/AirSim/AirLib/src/api/RpcLibClientBase.cpp index f0660dbd..099375c4 100644 --- a/AirSim/AirLib/src/api/RpcLibClientBase.cpp +++ b/AirSim/AirLib/src/api/RpcLibClientBase.cpp @@ -40,7 +40,7 @@ STRICT_MODE_OFF STRICT_MODE_ON #ifdef _MSC_VER __pragma(warning( disable : 4239)) -#endif +#endif namespace msr { namespace airlib { @@ -125,7 +125,7 @@ void RpcLibClientBase::confirmConnection(double timeout) clock->sleep_for(delay); } - + if (getConnectionState() != RpcLibClientBase::ConnectionState::Connected) { throw std::runtime_error("Failed connecting to RPC server (airsim). Is the simulator running?"); @@ -135,7 +135,7 @@ void RpcLibClientBase::confirmConnection(double timeout) auto client_ver = getClientVersion(); auto server_min_ver = getMinRequiredServerVersion(); auto client_min_ver = getMinRequiredClientVersion(); - + std::string ver_info = Utils::stringf("Client Ver:%i (Min Req:%i), Server Ver:%i (Min Req:%i)", client_ver, client_min_ver, server_ver, server_min_ver); @@ -208,6 +208,16 @@ void RpcLibClientBase::simSetVehiclePose(const Pose& pose, bool ignore_collision pimpl_->client.call("simSetVehiclePose", RpcLibAdapatorsBase::Pose(pose), ignore_collision, vehicle_name); } +void RpcLibClientBase::simResetToPose(const Pose& pose, const std::string& vehicle_name) +{ + pimpl_->client.call("simResetToPose", RpcLibAdapatorsBase::Pose(pose), vehicle_name); +} + +void RpcLibClientBase::simSetVehicleLinearVelocity(const Vector3r& velocity, const std::string& vehicle_name) +{ + pimpl_->client.call("simSetVehicleLinearVelocity", RpcLibAdapatorsBase::Vector3r(velocity), vehicle_name); +} + void RpcLibClientBase::simSetTraceLine(const std::vector& color_rgba, float thickness, const std::string & vehicle_name) { pimpl_->client.call("simSetTraceLine", color_rgba, thickness, vehicle_name); @@ -215,7 +225,7 @@ void RpcLibClientBase::simSetTraceLine(const std::vector& color_rgba, flo vector RpcLibClientBase::simGetImages(vector request, const std::string& vehicle_name) { - const auto& response_adaptor = pimpl_->client.call("simGetImages", + const auto& response_adaptor = pimpl_->client.call("simGetImages", RpcLibAdapatorsBase::ImageRequest::from(request), vehicle_name) .as>(); diff --git a/AirSim/AirLib/src/api/RpcLibServerBase.cpp b/AirSim/AirLib/src/api/RpcLibServerBase.cpp index fb709f3a..7ed68c34 100644 --- a/AirSim/AirLib/src/api/RpcLibServerBase.cpp +++ b/AirSim/AirLib/src/api/RpcLibServerBase.cpp @@ -49,7 +49,7 @@ struct RpcLibServerBase::impl { ~impl() { } - void stop() { + void stop() { server.close_sessions(); if (!is_async_) { // this deadlocks UI thread if async_run was called while there are pending rpc calls. @@ -92,20 +92,20 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& pimpl_->server.bind("getSettingsString", [&]() -> std::string { return getWorldSimApi()->getSettingsString(); }); - - pimpl_->server.bind("simPause", [&](bool is_paused) -> void { - getWorldSimApi()->pause(is_paused); + + pimpl_->server.bind("simPause", [&](bool is_paused) -> void { + getWorldSimApi()->pause(is_paused); }); - pimpl_->server.bind("simIsPaused", [&]() -> bool { - return getWorldSimApi()->isPaused(); + pimpl_->server.bind("simIsPaused", [&]() -> bool { + return getWorldSimApi()->isPaused(); }); - pimpl_->server.bind("simContinueForTime", [&](double seconds) -> void { - getWorldSimApi()->continueForTime(seconds); + pimpl_->server.bind("simContinueForTime", [&](double seconds) -> void { + getWorldSimApi()->continueForTime(seconds); }); - pimpl_->server.bind("simSetTimeOfDay", [&](bool is_enabled, const string& start_datetime, bool is_start_datetime_dst, + pimpl_->server.bind("simSetTimeOfDay", [&](bool is_enabled, const string& start_datetime, bool is_start_datetime_dst, float celestial_clock_speed, float update_interval_secs, bool move_sun) -> void { - getWorldSimApi()->setTimeOfDay(is_enabled, start_datetime, is_start_datetime_dst, + getWorldSimApi()->setTimeOfDay(is_enabled, start_datetime, is_start_datetime_dst, celestial_clock_speed, update_interval_secs, move_sun); }); @@ -116,13 +116,13 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& getWorldSimApi()->setWeatherParameter(param, val); }); - pimpl_->server.bind("enableApiControl", [&](bool is_enabled, const std::string& vehicle_name) -> void { + pimpl_->server.bind("enableApiControl", [&](bool is_enabled, const std::string& vehicle_name) -> void { getVehicleApi(vehicle_name)->enableApiControl(is_enabled); }); - pimpl_->server.bind("isApiControlEnabled", [&](const std::string& vehicle_name) -> bool { + pimpl_->server.bind("isApiControlEnabled", [&](const std::string& vehicle_name) -> bool { return getVehicleApi(vehicle_name)->isApiControlEnabled(); }); - pimpl_->server.bind("simGetImages", [&](const std::vector& request_adapter, const std::string& vehicle_name) -> + pimpl_->server.bind("simGetImages", [&](const std::vector& request_adapter, const std::string& vehicle_name) -> vector { const auto& response = getVehicleSimApi(vehicle_name)->getImages(RpcLibAdapatorsBase::ImageRequest::to(request_adapter)); return RpcLibAdapatorsBase::ImageResponse::from(response); @@ -150,6 +150,10 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return RpcLibAdapatorsBase::Pose(pose); }); + pimpl_->server.bind("simSetVehicleLinearVelocity", [&](const RpcLibAdapatorsBase::Vector3r& velocity, const std::string& vehicle_name) -> void { + getVehicleSimApi(vehicle_name)->setLinearVelocity(velocity.to()); + }); + pimpl_->server.bind("simSetTraceLine", [&](const std::vector& color_rgba, float thickness, const std::string& vehicle_name) -> void { getVehicleSimApi(vehicle_name)->setTraceLine(color_rgba, thickness); }); @@ -166,7 +170,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& pimpl_->server. bind("simGetSegmentationObjectID", [&](const std::string& mesh_name) -> int { return getWorldSimApi()->getSegmentationObjectID(mesh_name); - }); + }); pimpl_->server.bind("reset", [&]() -> void { //Exit if already resetting. @@ -184,6 +188,10 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& resetInProgress = false; }); + pimpl_->server.bind("simResetToPose", [&](const RpcLibAdapatorsBase::Pose& pose, const std::string& vehicle_name) -> void { + getWorldSimApi()->resetToPose(pose.to(), vehicle_name); + }); + pimpl_->server.bind("simPrintLogMessage", [&](const std::string& message, const std::string& message_param, unsigned char severity) -> void { getWorldSimApi()->printLogMessage(message, message_param, severity); }); @@ -223,7 +231,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return RpcLibAdapatorsBase::CameraInfo(camera_info); }); - pimpl_->server.bind("simSetCameraOrientation", [&](const std::string& camera_name, const RpcLibAdapatorsBase::Quaternionr& orientation, + pimpl_->server.bind("simSetCameraOrientation", [&](const std::string& camera_name, const RpcLibAdapatorsBase::Quaternionr& orientation, const std::string& vehicle_name) -> void { getVehicleSimApi(vehicle_name)->setCameraOrientation(camera_name, orientation.to()); }); @@ -234,7 +242,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& }); pimpl_->server.bind("simGetCollisionInfo", [&](const std::string& vehicle_name) -> RpcLibAdapatorsBase::CollisionInfo { - const auto& collision_info = getVehicleSimApi(vehicle_name)->getCollisionInfo(); + const auto& collision_info = getVehicleSimApi(vehicle_name)->getCollisionInfo(); return RpcLibAdapatorsBase::CollisionInfo(collision_info); }); @@ -243,7 +251,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& }); pimpl_->server.bind("simGetObjectPose", [&](const std::string& object_name) -> RpcLibAdapatorsBase::Pose { - const auto& pose = getWorldSimApi()->getObjectPose(object_name); + const auto& pose = getWorldSimApi()->getObjectPose(object_name); return RpcLibAdapatorsBase::Pose(pose); }); pimpl_->server.bind("simSetObjectPose", [&](const std::string& object_name, const RpcLibAdapatorsBase::Pose& pose, bool teleport) -> bool { diff --git a/UE4Project/Content/customMap.umap b/UE4Project/Content/customMap.umap old mode 100755 new mode 100644 index 06be086d..1de1d7d0 Binary files a/UE4Project/Content/customMap.umap and b/UE4Project/Content/customMap.umap differ diff --git a/UE4Project/Plugins/AirSim/Source/CoordFrameTransformer.cpp b/UE4Project/Plugins/AirSim/Source/CoordFrameTransformer.cpp index 3b8da023..26cfc5bb 100644 --- a/UE4Project/Plugins/AirSim/Source/CoordFrameTransformer.cpp +++ b/UE4Project/Plugins/AirSim/Source/CoordFrameTransformer.cpp @@ -34,6 +34,10 @@ CoordFrameTransformer::Vector3r CoordFrameTransformer::toLocalEnuVelocity(const { return CoordFrameTransformer::toVector3r(velocity, 1 / world_to_meters_); } +FVector CoordFrameTransformer::fromLocalEnuVelocity(const Vector3r& velocity) const +{ + return CoordFrameTransformer::toFVector(velocity, world_to_meters_); +} CoordFrameTransformer::Vector3r CoordFrameTransformer::toGlobalEnu(const FVector& position) const { return CoordFrameTransformer::toVector3r(position - global_transform_.GetLocation(), 1 / world_to_meters_); diff --git a/UE4Project/Plugins/AirSim/Source/CoordFrameTransformer.h b/UE4Project/Plugins/AirSim/Source/CoordFrameTransformer.h index 90880164..de24ae9a 100644 --- a/UE4Project/Plugins/AirSim/Source/CoordFrameTransformer.h +++ b/UE4Project/Plugins/AirSim/Source/CoordFrameTransformer.h @@ -29,6 +29,7 @@ class AIRSIM_API CoordFrameTransformer //UU -> local ENU Vector3r toLocalEnu(const FVector& position) const; Vector3r toLocalEnuVelocity(const FVector& velocity) const; + FVector fromLocalEnuVelocity(const Vector3r& velocity) const; Vector3r toGlobalEnu(const FVector& position) const; Quaternionr toEnu(const FQuat& q) const; float toEnu(float length) const; diff --git a/UE4Project/Plugins/AirSim/Source/SimMode/SimModeBase.cpp b/UE4Project/Plugins/AirSim/Source/SimMode/SimModeBase.cpp index 9005bbea..cf2d6ee8 100644 --- a/UE4Project/Plugins/AirSim/Source/SimMode/SimModeBase.cpp +++ b/UE4Project/Plugins/AirSim/Source/SimMode/SimModeBase.cpp @@ -53,7 +53,7 @@ void ASimModeBase::BeginPlay() //this must be done from within actor otherwise we don't get player start APlayerController* player_controller = this->GetWorld()->GetFirstPlayerController(); FTransform player_start_transform = player_controller->GetViewTarget()->GetActorTransform(); - global_ned_transform_.reset(new CoordFrameTransformer(player_start_transform, + global_ned_transform_.reset(new CoordFrameTransformer(player_start_transform, UAirBlueprintLib::GetWorldToMetersScale(this))); world_sim_api_.reset(new WorldSimApi(this)); @@ -62,7 +62,7 @@ void ASimModeBase::BeginPlay() setupClockSpeed(); setStencilIDs(); - + record_tick_count = 0; setupInputBindings(); @@ -109,7 +109,7 @@ void ASimModeBase::setStencilIDs() if (getSettings().segmentation_setting.init_method == AirSimSettings::SegmentationSetting::InitMethodType::CommonObjectsRandomIDs) { - + UAirBlueprintLib::InitializeMeshStencilIDs(!getSettings().segmentation_setting.override_existing); } //else don't init @@ -152,7 +152,7 @@ void ASimModeBase::initializeTimeOfDay() UObject* sun_obj = sun_prop->GetObjectPropertyValue_InContainer(sky_sphere_); sun_ = Cast(sun_obj); if (sun_) - default_sun_rotation_ = sun_->GetActorRotation(); + default_sun_rotation_ = sun_->GetActorRotation(); } } @@ -160,7 +160,7 @@ void ASimModeBase::setTimeOfDay(bool is_enabled, const std::string& start_dateti float celestial_clock_speed, float update_interval_secs, bool move_sun) { bool enabled_currently = tod_enabled_; - + if (is_enabled) { if (!sun_) { @@ -170,7 +170,7 @@ void ASimModeBase::setTimeOfDay(bool is_enabled, const std::string& start_dateti else { sun_->GetRootComponent()->Mobility = EComponentMobility::Movable; - // this is a bit odd but given how advanceTimeOfDay() works currently, + // this is a bit odd but given how advanceTimeOfDay() works currently, // tod_sim_clock_start_ needs to be reset here. tod_sim_clock_start_ = ClockFactory::get()->nowNanos(); @@ -256,8 +256,8 @@ void ASimModeBase::showClockStats() { float clock_speed = getSettings().clock_speed; if (clock_speed != 1) { - UAirBlueprintLib::LogMessageString("ClockSpeed config, actual: ", - Utils::stringf("%f, %f", clock_speed, ClockFactory::get()->getTrueScaleWrtWallClock()), + UAirBlueprintLib::LogMessageString("ClockSpeed config, actual: ", + Utils::stringf("%f, %f", clock_speed, ClockFactory::get()->getTrueScaleWrtWallClock()), LogDebugLevel::Informational); } } @@ -306,6 +306,11 @@ void ASimModeBase::reset() }, true); } +void ASimModeBase::resetToPose(const msr::airlib::Pose& pose, const std::string& vehicle_name) +{ + getVehicleSimApi(vehicle_name)->resetToPose(pose); +} + void ASimModeBase::setupInputBindings() { UAirBlueprintLib::EnableInput(this); @@ -332,13 +337,13 @@ void ASimModeBase::initializeCameraDirector(const FTransform& camera_transform, FActorSpawnParameters camera_spawn_params; camera_spawn_params.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AdjustIfPossibleButAlwaysSpawn; camera_spawn_params.Name = "CameraDirector"; - CameraDirector = this->GetWorld()->SpawnActor(camera_director_class_, + CameraDirector = this->GetWorld()->SpawnActor(camera_director_class_, camera_transform, camera_spawn_params); CameraDirector->setFollowDistance(follow_distance); CameraDirector->setCameraRotationLagEnabled(false); //create external camera required for the director camera_spawn_params.Name = "ExternalCamera"; - CameraDirector->ExternalCamera = this->GetWorld()->SpawnActor(external_camera_class_, + CameraDirector->ExternalCamera = this->GetWorld()->SpawnActor(external_camera_class_, camera_transform, camera_spawn_params); } else { @@ -400,9 +405,9 @@ void ASimModeBase::setupVehiclesAndCamera() //determine camera director camera default pose and spawn it const auto& camera_director_setting = getSettings().camera_director; - FVector camera_director_position_uu = uu_origin.GetLocation() + + FVector camera_director_position_uu = uu_origin.GetLocation() + getGlobalNedTransform().fromLocalEnu(camera_director_setting.position); - FTransform camera_transform(toFRotator(camera_director_setting.rotation, FRotator::ZeroRotator), + FTransform camera_transform(toFRotator(camera_director_setting.rotation, FRotator::ZeroRotator), camera_director_position_uu); initializeCameraDirector(camera_transform, camera_director_setting.follow_distance); @@ -459,7 +464,7 @@ void ASimModeBase::setupVehiclesAndCamera() const std::string vehicle_name = std::string(TCHAR_TO_UTF8(*(vehicle_pawn->GetName()))); CarPawnSimApi::Params pawn_sim_api_params(vehicle_pawn, &getGlobalNedTransform(), - getVehiclePawnEvents(vehicle_pawn), getVehiclePawnCameras(vehicle_pawn), pip_camera_class, + getVehiclePawnEvents(vehicle_pawn), getVehiclePawnCameras(vehicle_pawn), pip_camera_class, home_geopoint, vehicle_name); auto vehicle_sim_api = createVehicleSimApi(pawn_sim_api_params); @@ -543,7 +548,7 @@ void ASimModeBase::drawLidarDebugPoints() msr::airlib::VehicleApiBase* api = getApiProvider()->getVehicleApi(vehicle_name); if (api != nullptr) { - + msr::airlib::uint count_lidars = api->getSensors().size(msr::airlib::SensorBase::SensorType::Lidar); for (msr::airlib::uint i = 0; i < count_lidars; i++) { diff --git a/UE4Project/Plugins/AirSim/Source/SimMode/SimModeBase.h b/UE4Project/Plugins/AirSim/Source/SimMode/SimModeBase.h index 3579f041..bc4104dc 100644 --- a/UE4Project/Plugins/AirSim/Source/SimMode/SimModeBase.h +++ b/UE4Project/Plugins/AirSim/Source/SimMode/SimModeBase.h @@ -31,14 +31,14 @@ class AIRSIM_API ASimModeBase : public AActor UFUNCTION(BlueprintCallable, Category = "Api") void startApiServer(); - + UFUNCTION(BlueprintCallable, Category = "Api") void stopApiServer(); UFUNCTION(BlueprintCallable, Category = "Api") bool isApiServerStarted(); -public: +public: // Sets default values for this actor's properties ASimModeBase(); virtual void BeginPlay() override; @@ -47,6 +47,7 @@ class AIRSIM_API ASimModeBase : public AActor //additional overridable methods virtual void reset(); + virtual void resetToPose(const msr::airlib::Pose& pose, const std::string& vehicle_name = ""); virtual ECameraDirectorMode getInitialViewMode() const; virtual bool isPaused() const; diff --git a/UE4Project/Plugins/AirSim/Source/Vehicles/Car/CarPawnSimApi.cpp b/UE4Project/Plugins/AirSim/Source/Vehicles/Car/CarPawnSimApi.cpp index 45e3b5c4..6db36d17 100644 --- a/UE4Project/Plugins/AirSim/Source/Vehicles/Car/CarPawnSimApi.cpp +++ b/UE4Project/Plugins/AirSim/Source/Vehicles/Car/CarPawnSimApi.cpp @@ -185,6 +185,24 @@ void CarPawnSimApi::resetImplementation() resetPawn(); } +void CarPawnSimApi::resetToPose(const Pose& pose) +{ + setPoseInternal(pose, true); + kinematics_->reset(); + resetPawn(); +} + +void CarPawnSimApi::setLinearVelocity(const msr::airlib::Vector3r& velocity) +{ + FVector velocity_uu = ned_transform_.fromLocalEnuVelocity(velocity); + auto phys_comps = UAirBlueprintLib::getPhysicsComponents(pawn_); + UAirBlueprintLib::RunCommandOnGameThread([velocity_uu, &phys_comps]() { + for (auto* phys_comp : phys_comps) { + phys_comp->SetPhysicsLinearVelocity(velocity_uu, false, NAME_None); + } + }, true); +} + //physics tick void CarPawnSimApi::update() { @@ -206,7 +224,7 @@ void CarPawnSimApi::setStartPosition(const FVector& position, const FRotator& ro //compute our home point Vector3r nedWrtOrigin = ned_transform_.toGlobalEnu(initial_state_.start_location); - home_geo_point_ = msr::airlib::EarthUtils::nedToGeodetic(nedWrtOrigin, + home_geo_point_ = msr::airlib::EarthUtils::nedToGeodetic(nedWrtOrigin, AirSimSettings::singleton().origin_geopoint); } @@ -284,7 +302,7 @@ void CarPawnSimApi::createCamerasFromSettings() } } -void CarPawnSimApi::onCollision(class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp, +void CarPawnSimApi::onCollision(class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp, bool bSelfMoved, FVector HitLocation, FVector HitNormal, FVector NormalImpulse, const FHitResult& Hit) { // Deflect along the surface when we collide. @@ -305,8 +323,8 @@ void CarPawnSimApi::onCollision(class UPrimitiveComponent* MyComp, class AActor* ++state_.collision_info.collision_count; - UAirBlueprintLib::LogMessageString("Collision", Utils::stringf("#%d with %s - ObjID %d", - state_.collision_info.collision_count, + UAirBlueprintLib::LogMessageString("Collision", Utils::stringf("#%d with %s - ObjID %d", + state_.collision_info.collision_count, state_.collision_info.object_name.c_str(), state_.collision_info.object_id), LogDebugLevel::Informational); } @@ -380,7 +398,7 @@ msr::airlib::RCData CarPawnSimApi::getRCData() const rc_data_.switches = joystick_state_.buttons; rc_data_.vendor_id = joystick_state_.pid_vid.substr(0, joystick_state_.pid_vid.find('&')); - + //switch index 0 to 7 for FrSky Taranis RC is: //front-upper-left, front-upper-right, top-right-left, top-right-left, top-left-right, top-right-right, top-left-left, top-right-left @@ -443,7 +461,7 @@ void CarPawnSimApi::toggleTrace() if (!state_.tracing_enabled) UKismetSystemLibrary::FlushPersistentDebugLines(params_.pawn->GetWorld()); - else { + else { state_.debug_position_offset = state_.current_debug_position - state_.current_position; state_.last_debug_position = state_.last_position; } @@ -591,7 +609,7 @@ void CarPawnSimApi::updateKinematics(float dt) kinematics_->update(); } -float computeAngleChange(float prev_rotation_angle_rad, float new_rotation_angle_rad) +float computeAngleChange(float prev_rotation_angle_rad, float new_rotation_angle_rad) { return new_rotation_angle_rad + (new_rotation_angle_rad > prev_rotation_angle_rad ? 0.0f : 2.0f * M_PI) - prev_rotation_angle_rad; } @@ -608,7 +626,7 @@ void CarPawnSimApi::updateWheelStates() // at very low velocities the angular velocity becomes very unstable, // so a higher smoothing factor is needed to obtain a usable estimate - float higher_smoothing_factor_rpm_threshold = 80; + float higher_smoothing_factor_rpm_threshold = 80; float avg_rear_wheel_rpm = (wheel_states_->rr.rpm + wheel_states_->rl.rpm) / 2; float rpm_smoothing_coeff = 0.7; if (avg_rear_wheel_rpm < higher_smoothing_factor_rpm_threshold) { diff --git a/UE4Project/Plugins/AirSim/Source/Vehicles/Car/CarPawnSimApi.h b/UE4Project/Plugins/AirSim/Source/Vehicles/Car/CarPawnSimApi.h index 48857800..898d2d9d 100644 --- a/UE4Project/Plugins/AirSim/Source/Vehicles/Car/CarPawnSimApi.h +++ b/UE4Project/Plugins/AirSim/Source/Vehicles/Car/CarPawnSimApi.h @@ -44,7 +44,7 @@ class CarPawnSimApi : public msr::airlib::VehicleSimApiBase typedef msr::airlib::ImageCaptureBase ImageCaptureBase; struct Params { - APawn* pawn; + APawn* pawn; const CoordFrameTransformer* global_transform; PawnEvents* pawn_events; common_utils::UniqueValueMap cameras; @@ -61,7 +61,7 @@ class CarPawnSimApi : public msr::airlib::VehicleSimApiBase const msr::airlib::GeoPoint home_geopoint_val, std::string vehicle_name_val) { - pawn = pawn_val; + pawn = pawn_val; global_transform = global_transform_val; pawn_events = pawn_events_val; cameras = cameras_val; @@ -100,6 +100,8 @@ class CarPawnSimApi : public msr::airlib::VehicleSimApiBase virtual std::vector getImage(const std::string& camera_name, ImageCaptureBase::ImageType image_type) const override; virtual Pose getPose() const override; virtual void setPose(const Pose& pose, bool ignore_collision) override; + virtual void resetToPose(const Pose& pose) override; + virtual void setLinearVelocity(const msr::airlib::Vector3r& velocity) override; virtual msr::airlib::CameraInfo getCameraInfo(const std::string& camera_name) const override; const APIPCamera* getCamera(const std::string& camera_name) const; @@ -202,7 +204,7 @@ class CarPawnSimApi : public msr::airlib::VehicleSimApiBase FVector last_debug_position; FVector current_position; FVector current_debug_position; - FVector debug_position_offset; + FVector debug_position_offset; bool tracing_enabled; bool collisions_enabled; bool passthrough_enabled; @@ -214,7 +216,7 @@ class CarPawnSimApi : public msr::airlib::VehicleSimApiBase FVector ground_offset; FVector transformation_offset; }; - + State state_, initial_state_; std::unique_ptr kinematics_; diff --git a/UE4Project/Plugins/AirSim/Source/WorldSimApi.cpp b/UE4Project/Plugins/AirSim/Source/WorldSimApi.cpp index 44b1354a..6b8fba1c 100644 --- a/UE4Project/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/UE4Project/Plugins/AirSim/Source/WorldSimApi.cpp @@ -19,10 +19,17 @@ bool WorldSimApi::isPaused() const void WorldSimApi::reset() { UAirBlueprintLib::RunCommandOnGameThread([this]() { - simmode_->reset(); + simmode_->reset(); }, true); } +void WorldSimApi::resetToPose(const Pose& pose, const std::string& vehicle_name) +{ + UAirBlueprintLib::RunCommandOnGameThread([this, pose, vehicle_name]() { + simmode_->resetToPose(pose, vehicle_name); + }, true); +} + void WorldSimApi::pause(bool is_paused) { simmode_->pause(is_paused); @@ -101,7 +108,7 @@ bool WorldSimApi::setObjectPose(const std::string& object_name, const WorldSimAp FTransform actor_transform = simmode_->getGlobalNedTransform().fromGlobalEnu(pose); AActor* actor = UAirBlueprintLib::FindActor(simmode_, FString(object_name.c_str())); if (actor) { - if (teleport) + if (teleport) result = actor->SetActorLocationAndRotation(actor_transform.GetLocation(), actor_transform.GetRotation(), false, nullptr, ETeleportType::TeleportPhysics); else result = actor->SetActorLocationAndRotation(actor_transform.GetLocation(), actor_transform.GetRotation(), true); @@ -153,7 +160,7 @@ std::unique_ptr> WorldSimApi::swapTextures(const std::s if (invalidChoice) break; } - + if (invalidChoice) continue; dynamic_cast(shuffler)->SwapTexture(tex_id, component_id, material_id); diff --git a/UE4Project/Plugins/AirSim/Source/WorldSimApi.h b/UE4Project/Plugins/AirSim/Source/WorldSimApi.h index a6777af1..d7ef2314 100644 --- a/UE4Project/Plugins/AirSim/Source/WorldSimApi.h +++ b/UE4Project/Plugins/AirSim/Source/WorldSimApi.h @@ -18,6 +18,7 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase { virtual bool isPaused() const override; virtual void reset() override; + virtual void resetToPose(const Pose& pose, const std::string& vehicle_name = "") override; virtual void pause(bool is_paused) override; virtual void continueForTime(double seconds) override; diff --git a/python/.gitignore b/python/.gitignore new file mode 100644 index 00000000..8c4c7c7f --- /dev/null +++ b/python/.gitignore @@ -0,0 +1,216 @@ +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[codz] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +share/python-wheels/ +*.egg-info/ +.installed.cfg +*.egg +MANIFEST + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.nox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*.cover +*.py.cover +.hypothesis/ +.pytest_cache/ +cover/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py +db.sqlite3 +db.sqlite3-journal + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +.pybuilder/ +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# IPython +profile_default/ +ipython_config.py + +# pyenv +# For a library or package, you might want to ignore these files since the code is +# intended to run in multiple environments; otherwise, check them in: +# .python-version + +# pipenv +# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control. +# However, in case of collaboration, if having platform-specific dependencies or dependencies +# having no cross-platform support, pipenv may install dependencies that don't work, or not +# install all needed dependencies. +# Pipfile.lock + +# UV +# Similar to Pipfile.lock, it is generally recommended to include uv.lock in version control. +# This is especially recommended for binary packages to ensure reproducibility, and is more +# commonly ignored for libraries. +# uv.lock + +# poetry +# Similar to Pipfile.lock, it is generally recommended to include poetry.lock in version control. +# This is especially recommended for binary packages to ensure reproducibility, and is more +# commonly ignored for libraries. +# https://python-poetry.org/docs/basic-usage/#commit-your-poetrylock-file-to-version-control +# poetry.lock +# poetry.toml + +# pdm +# Similar to Pipfile.lock, it is generally recommended to include pdm.lock in version control. +# pdm recommends including project-wide configuration in pdm.toml, but excluding .pdm-python. +# https://pdm-project.org/en/latest/usage/project/#working-with-version-control +# pdm.lock +# pdm.toml +.pdm-python +.pdm-build/ + +# pixi +# Similar to Pipfile.lock, it is generally recommended to include pixi.lock in version control. +# pixi.lock +# Pixi creates a virtual environment in the .pixi directory, just like venv module creates one +# in the .venv directory. It is recommended not to include this directory in version control. +.pixi + +# PEP 582; used by e.g. github.com/David-OConnor/pyflow and github.com/pdm-project/pdm +__pypackages__/ + +# Celery stuff +celerybeat-schedule +celerybeat.pid + +# Redis +*.rdb +*.aof +*.pid + +# RabbitMQ +mnesia/ +rabbitmq/ +rabbitmq-data/ + +# ActiveMQ +activemq-data/ + +# SageMath parsed files +*.sage.py + +# Environments +.env +.envrc +.venv +env/ +venv/ +ENV/ +env.bak/ +venv.bak/ + +# Spyder project settings +.spyderproject +.spyproject + +# Rope project settings +.ropeproject + +# mkdocs documentation +/site + +# mypy +.mypy_cache/ +.dmypy.json +dmypy.json + +# Pyre type checker +.pyre/ + +# pytype static type analyzer +.pytype/ + +# Cython debug symbols +cython_debug/ + +# PyCharm +# JetBrains specific template is maintained in a separate JetBrains.gitignore that can +# be found at https://github.com/github/gitignore/blob/main/Global/JetBrains.gitignore +# and can be added to the global gitignore or merged into this file. For a more nuclear +# option (not recommended) you can uncomment the following to ignore the entire idea folder. +# .idea/ + +# Abstra +# Abstra is an AI-powered process automation framework. +# Ignore directories containing user credentials, local state, and settings. +# Learn more at https://abstra.io/docs +.abstra/ + +# Visual Studio Code +# Visual Studio Code specific template is maintained in a separate VisualStudioCode.gitignore +# that can be found at https://github.com/github/gitignore/blob/main/Global/VisualStudioCode.gitignore +# and can be added to the global gitignore or merged into this file. However, if you prefer, +# you could uncomment the following to ignore the entire vscode folder +# .vscode/ + +# Ruff stuff: +.ruff_cache/ + +# PyPI configuration file +.pypirc + +# Marimo +marimo/_static/ +marimo/_lsp/ +__marimo__/ + +# Streamlit +.streamlit/secrets.toml diff --git a/python/pyproject.toml b/python/pyproject.toml new file mode 100644 index 00000000..185a8f94 --- /dev/null +++ b/python/pyproject.toml @@ -0,0 +1,28 @@ +[project] +name = "fsds" +version = "0.1.0" +description = "Python client for the Formula Student Driverless Simulator (FSDS)" +readme = { file = "README.md", content-type = "text/markdown" } +requires-python = ">=3.12" +license = { text = "GPL-2.0-or-later" } +authors = [ + { name = "Formula Student Driverless Simulator Contributors" } +] +dependencies = [ + "msgpack-rpc-python @ git+https://github.com/vctr-dng/msgpack-rpc-python.git@fsds-python-pkg", + "backports.ssl_match_hostname", # required for msgpack-rpc-python + "numpy", + "opencv-contrib-python", +] + +[project.urls] +Homepage = "https://github.com/vctr-dng/Formula-Student-Driverless-Simulator" +Repository = "https://github.com/vctr-dng/Formula-Student-Driverless-Simulator" + +[build-system] +requires = ["uv_build >= 0.9.21, <0.10.0"] +build-backend = "uv_build" + +[tool.uv.build-backend] +module-name = "fsds" +module-root = ""