3#include <message_filters/subscriber.h>
4#include <message_filters/sync_policies/approximate_time.h>
5#include <message_filters/synchronizer.h>
6#include <message_filters/time_synchronizer.h>
8#include <std_srvs/srv/empty.hpp>
11#include "pacsim/msg/perception_detections.hpp"
12#include "pacsim/msg/stamped_scalar.hpp"
13#include "pacsim/msg/wheels.hpp"
18 message_filters::Subscriber<pacsim::msg::Wheels>
20 message_filters::Subscriber<pacsim::msg::StampedScalar>
25 pacsim::msg::StampedScalar>;
26 std::shared_ptr<message_filters::Synchronizer<WheelSteerPolicy>>
29 rclcpp::Subscription<pacsim::msg::PerceptionDetections>::SharedPtr
32 rclcpp::Client<std_srvs::srv::Empty>::SharedPtr
40 const pacsim::msg::StampedScalar& steering_angle_msg);
Class that handles the communication between the SpeedEstimation node and the other nodes in the syst...
Adapter class to interface with the Pacsim simulator for SLAM.
rclcpp::Subscription< pacsim::msg::PerceptionDetections >::SharedPtr _perception_detections_subscription_
Subscriber for simulated perception detections.
message_filters::Subscriber< pacsim::msg::Wheels > _pacsim_wheel_speeds_subscription_
Subscriber for wheel speeds.
message_filters::sync_policies::ApproximateTime< pacsim::msg::Wheels, pacsim::msg::StampedScalar > WheelSteerPolicy
Policy for synchronizing wheel speeds and steering angle.
std::shared_ptr< message_filters::Synchronizer< WheelSteerPolicy > > _sync_
Synchronizer for wheel speeds and steering angle.
void perception_detections_subscription_callback(const pacsim::msg::PerceptionDetections &msg)
Callback for simulated perception detections from pacsim.
void wheel_speeds_subscription_callback(const pacsim::msg::Wheels &wheels_msg, const pacsim::msg::StampedScalar &steering_angle_msg)
Wheel speed subscription callback, which receives both wheel speeds and steering angle through a sync...
void finish() final
Function that sends the finish signal to the respective node.
rclcpp::Client< std_srvs::srv::Empty >::SharedPtr _finished_client_
Client for finished signal.
message_filters::Subscriber< pacsim::msg::StampedScalar > _steering_angle_subscription_
Subscriber for steering angle.
Class representing the main speed_est node responsible for publishing the calculated vehicle state wi...