VehicleModelComponent.cpp 5.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137
  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 "VehicleModelLimits.h"
  12. #include <AzCore/Debug/Trace.h>
  13. #include <AzCore/Serialization/EditContext.h>
  14. #include <AzCore/Serialization/EditContextConstants.inl>
  15. #include <AzCore/Serialization/SerializeContext.h>
  16. #include <AzCore/std/smart_ptr/make_shared.h>
  17. #include <AzFramework/Physics/RigidBodyBus.h>
  18. #include <ROS2Controllers/VehicleDynamics/VehicleConfiguration.h>
  19. namespace ROS2Controllers::VehicleDynamics
  20. {
  21. void VehicleModelComponent::Activate()
  22. {
  23. VehicleInputControlRequestBus::Handler::BusConnect(GetEntityId());
  24. if (m_enableManualControl)
  25. {
  26. m_manualControlEventHandler.Activate(GetEntityId());
  27. }
  28. AZ::TickBus::Handler::BusConnect();
  29. }
  30. void VehicleModelComponent::Deactivate()
  31. {
  32. AZ::TickBus::Handler::BusDisconnect();
  33. m_manualControlEventHandler.Deactivate();
  34. VehicleInputControlRequestBus::Handler::BusDisconnect();
  35. }
  36. void VehicleModelComponent::Reflect(AZ::ReflectContext* context)
  37. {
  38. VehicleConfiguration::Reflect(context);
  39. VehicleModelLimits::Reflect(context);
  40. DriveModel::Reflect(context);
  41. if (AZ::SerializeContext* serialize = azrtti_cast<AZ::SerializeContext*>(context))
  42. {
  43. serialize->Class<VehicleModelComponent, AZ::Component>()
  44. ->Version(4)
  45. ->Field("VehicleConfiguration", &VehicleModelComponent::m_vehicleConfiguration)
  46. ->Field("ManualControl", &VehicleModelComponent::m_enableManualControl);
  47. if (AZ::EditContext* ec = serialize->GetEditContext())
  48. {
  49. ec->Class<VehicleModelComponent>("Vehicle Model", "Customizable vehicle model component")
  50. ->DataElement(
  51. AZ::Edit::UIHandlers::Default,
  52. &VehicleModelComponent::m_vehicleConfiguration,
  53. "Vehicle settings",
  54. "Vehicle settings including axles and common wheel parameters")
  55. ->DataElement(
  56. AZ::Edit::UIHandlers::Default,
  57. &VehicleModelComponent::m_enableManualControl,
  58. "Enable Manual Control",
  59. "Enable manual control of the vehicle");
  60. }
  61. }
  62. }
  63. void VehicleModelComponent::SetTargetLinearSpeed(float speedMpsX)
  64. {
  65. m_inputsState.m_speed.UpdateValue({ speedMpsX, 0, 0 });
  66. }
  67. void VehicleModelComponent::SetTargetLinearSpeedV3(const AZ::Vector3& speedMps)
  68. {
  69. m_inputsState.m_speed.UpdateValue(speedMps);
  70. }
  71. void VehicleModelComponent::SetTargetLinearSpeedFraction(float speedFractionX)
  72. {
  73. const auto& maxState = GetDriveModel()->GetMaximumPossibleInputs();
  74. m_inputsState.m_speed.UpdateValue(maxState.m_speed * speedFractionX);
  75. }
  76. void VehicleModelComponent::SetTargetAccelerationFraction([[maybe_unused]] float accelerationFraction)
  77. {
  78. AZ_Error("SetTargetAccelerationFraction", false, "Not implemented");
  79. }
  80. void VehicleModelComponent::SetDisableVehicleDynamics(bool isDisable)
  81. {
  82. GetDriveModel()->SetDisabled(isDisable);
  83. }
  84. void VehicleModelComponent::SetTargetSteering(float steering)
  85. {
  86. m_inputsState.m_jointRequestedPosition.UpdateValue({ steering });
  87. }
  88. void VehicleModelComponent::SetTargetSteeringFraction(float steeringFraction)
  89. {
  90. const auto& maxState = GetDriveModel()->GetMaximumPossibleInputs();
  91. if (!maxState.m_jointRequestedPosition.empty())
  92. {
  93. m_inputsState.m_jointRequestedPosition.UpdateValue({ maxState.m_jointRequestedPosition.front() * steeringFraction });
  94. }
  95. }
  96. void VehicleModelComponent::SetTargetAngularSpeed(float rateZ)
  97. {
  98. m_inputsState.m_angularRates.UpdateValue({ 0, 0, rateZ });
  99. };
  100. void VehicleModelComponent::SetTargetAngularSpeedV3(const AZ::Vector3& rate)
  101. {
  102. m_inputsState.m_angularRates.UpdateValue(rate);
  103. };
  104. void VehicleModelComponent::SetTargetAngularSpeedFraction(float rateFractionZ)
  105. {
  106. const auto& maxState = GetDriveModel()->GetMaximumPossibleInputs();
  107. m_inputsState.m_angularRates.UpdateValue(maxState.m_angularRates * rateFractionZ);
  108. };
  109. void VehicleModelComponent::OnTick(float deltaTime, [[maybe_unused]] AZ::ScriptTimePoint time)
  110. {
  111. const uint64_t deltaTimeNs = deltaTime * 1'000'000'000;
  112. GetDriveModel()->ApplyInputState(m_inputsState.GetValueCheckingDeadline(), deltaTimeNs);
  113. }
  114. AZStd::pair<AZ::Vector3, AZ::Vector3> VehicleModelComponent::GetWheelsOdometry()
  115. {
  116. return GetDriveModel()->GetVelocityFromModel();
  117. }
  118. } // namespace ROS2Controllers::VehicleDynamics