ROS2WheelOdometry.h 2.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950
  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. #pragma once
  9. #include <AzCore/Math/Transform.h>
  10. #include <nav_msgs/msg/odometry.hpp>
  11. #include <rclcpp/publisher.hpp>
  12. #include <ROS2/Sensor/Events/PhysicsBasedSource.h>
  13. #include <ROS2/Sensor/ROS2SensorComponentBase.h>
  14. #include "ROS2OdometryCovariance.h"
  15. namespace ROS2
  16. {
  17. //! Wheel odometry sensor component.
  18. //! It constructs and publishes an odometry message, which contains information about the vehicle's velocity and position in space.
  19. //! This is a physical sensor that takes a vehicle's configuration and computes updates from the wheels' rotations.
  20. //! @see <a href="https://index.ros.org/p/nav_msgs/">nav_msgs package</a>.
  21. class ROS2WheelOdometryComponent
  22. : public ROS2SensorComponentBase<PhysicsBasedSource>
  23. {
  24. public:
  25. AZ_COMPONENT(ROS2WheelOdometryComponent, ROS2WheelOdometryComponentTypeId, SensorBaseType);
  26. ROS2WheelOdometryComponent();
  27. ~ROS2WheelOdometryComponent() = default;
  28. static void GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required);
  29. static void Reflect(AZ::ReflectContext* context);
  30. //////////////////////////////////////////////////////////////////////////
  31. // Component overrides
  32. void Activate() override;
  33. void Deactivate() override;
  34. //////////////////////////////////////////////////////////////////////////
  35. private:
  36. std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> m_odometryPublisher;
  37. nav_msgs::msg::Odometry m_odometryMsg;
  38. AZ::Vector3 m_robotPose{ 0 };
  39. AZ::Quaternion m_robotRotation{ 0, 0, 0, 1 };
  40. ROS2OdometryCovariance m_poseCovariance;
  41. ROS2OdometryCovariance m_twistCovariance;
  42. void OnOdometryEvent();
  43. void OnPhysicsEvent(float physicsDeltaTime);
  44. };
  45. } // namespace ROS2