VehicleModelComponent.cpp 4.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120
  1. /*
  2. * Copyright (c) Contributors to the Open 3D Engine Project.
  3. * For complete copyright and license terms please see the LICENSE at the root of this distribution.
  4. *
  5. * SPDX-License-Identifier: Apache-2.0 OR MIT
  6. *
  7. */
  8. #include "VehicleModelComponent.h"
  9. #include "DriveModels/AckermannDriveModel.h"
  10. #include "Utilities.h"
  11. #include "VehicleConfiguration.h"
  12. #include "VehicleModelLimits.h"
  13. #include <AzCore/Debug/Trace.h>
  14. #include <AzCore/Serialization/EditContext.h>
  15. #include <AzCore/Serialization/EditContextConstants.inl>
  16. #include <AzCore/Serialization/SerializeContext.h>
  17. #include <AzCore/std/smart_ptr/make_shared.h>
  18. #include <AzFramework/Physics/RigidBodyBus.h>
  19. namespace ROS2::VehicleDynamics
  20. {
  21. void VehicleModelComponent::Activate()
  22. {
  23. VehicleInputControlRequestBus::Handler::BusConnect(GetEntityId());
  24. m_manualControlEventHandler.Activate(GetEntityId());
  25. AZ::TickBus::Handler::BusConnect();
  26. }
  27. void VehicleModelComponent::Deactivate()
  28. {
  29. AZ::TickBus::Handler::BusDisconnect();
  30. m_manualControlEventHandler.Deactivate();
  31. VehicleInputControlRequestBus::Handler::BusDisconnect();
  32. }
  33. void VehicleModelComponent::Reflect(AZ::ReflectContext* context)
  34. {
  35. VehicleConfiguration::Reflect(context);
  36. VehicleModelLimits::Reflect(context);
  37. DriveModel::Reflect(context);
  38. if (AZ::SerializeContext* serialize = azrtti_cast<AZ::SerializeContext*>(context))
  39. {
  40. serialize->Class<VehicleModelComponent, AZ::Component>()->Version(4)->Field(
  41. "VehicleConfiguration", &VehicleModelComponent::m_vehicleConfiguration);
  42. if (AZ::EditContext* ec = serialize->GetEditContext())
  43. {
  44. ec->Class<VehicleModelComponent>("Vehicle Model", "Customizable vehicle model component")
  45. ->DataElement(
  46. AZ::Edit::UIHandlers::Default,
  47. &VehicleModelComponent::m_vehicleConfiguration,
  48. "Vehicle settings",
  49. "Vehicle settings including axles and common wheel parameters");
  50. }
  51. }
  52. }
  53. void VehicleModelComponent::SetTargetLinearSpeed(float speedMpsX)
  54. {
  55. m_inputsState.m_speed.UpdateValue({ speedMpsX, 0, 0 });
  56. }
  57. void VehicleModelComponent::SetTargetLinearSpeedV3(const AZ::Vector3& speedMps)
  58. {
  59. m_inputsState.m_speed.UpdateValue(speedMps);
  60. }
  61. void VehicleModelComponent::SetTargetLinearSpeedFraction(float speedFractionX)
  62. {
  63. const auto& maxState = GetDriveModel()->GetMaximumPossibleInputs();
  64. m_inputsState.m_speed.UpdateValue(maxState.m_speed * speedFractionX);
  65. }
  66. void VehicleModelComponent::SetTargetAccelerationFraction([[maybe_unused]] float accelerationFraction)
  67. {
  68. AZ_Error("SetTargetAccelerationFraction", false, "Not implemented");
  69. }
  70. void VehicleModelComponent::SetDisableVehicleDynamics(bool isDisable)
  71. {
  72. GetDriveModel()->SetDisabled(isDisable);
  73. }
  74. void VehicleModelComponent::SetTargetSteering(float steering)
  75. {
  76. m_inputsState.m_jointRequestedPosition.UpdateValue({ steering });
  77. }
  78. void VehicleModelComponent::SetTargetSteeringFraction(float steeringFraction)
  79. {
  80. const auto& maxState = GetDriveModel()->GetMaximumPossibleInputs();
  81. if (!maxState.m_jointRequestedPosition.empty())
  82. {
  83. m_inputsState.m_jointRequestedPosition.UpdateValue({ maxState.m_jointRequestedPosition.front() * steeringFraction });
  84. }
  85. }
  86. void VehicleModelComponent::SetTargetAngularSpeed(float rateZ)
  87. {
  88. m_inputsState.m_angularRates.UpdateValue({ 0, 0, rateZ });
  89. };
  90. void VehicleModelComponent::SetTargetAngularSpeedV3(const AZ::Vector3& rate)
  91. {
  92. m_inputsState.m_angularRates.UpdateValue(rate);
  93. };
  94. void VehicleModelComponent::SetTargetAngularSpeedFraction(float rateFractionZ)
  95. {
  96. const auto& maxState = GetDriveModel()->GetMaximumPossibleInputs();
  97. m_inputsState.m_angularRates.UpdateValue(maxState.m_angularRates * rateFractionZ);
  98. };
  99. void VehicleModelComponent::OnTick(float deltaTime, [[maybe_unused]] AZ::ScriptTimePoint time)
  100. {
  101. const uint64_t deltaTimeNs = deltaTime * 1'000'000'000;
  102. GetDriveModel()->ApplyInputState(m_inputsState.GetValueCheckingDeadline(), deltaTimeNs);
  103. }
  104. } // namespace ROS2::VehicleDynamics