Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
pacsim.hpp
Go to the documentation of this file.
1#pragma once
2
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>
7
8#include <std_srvs/srv/empty.hpp>
9
11#include "pacsim/msg/perception_detections.hpp"
12#include "pacsim/msg/stamped_scalar.hpp"
13#include "pacsim/msg/wheels.hpp"
14
15class SENode;
16
17class PacsimAdapter : public Adapter {
18 message_filters::Subscriber<pacsim::msg::Wheels>
20 message_filters::Subscriber<pacsim::msg::StampedScalar>
22
23 using WheelSteerPolicy = message_filters::sync_policies::ApproximateTime<
24 pacsim::msg::Wheels,
25 pacsim::msg::StampedScalar>;
26 std::shared_ptr<message_filters::Synchronizer<WheelSteerPolicy>>
28
29 rclcpp::Subscription<pacsim::msg::PerceptionDetections>::SharedPtr
31
32 rclcpp::Client<std_srvs::srv::Empty>::SharedPtr
34
39 void wheel_speeds_subscription_callback(const pacsim::msg::Wheels& wheels_msg,
40 const pacsim::msg::StampedScalar& steering_angle_msg);
41
47 void perception_detections_subscription_callback(const pacsim::msg::PerceptionDetections& msg);
48
49public:
50 explicit PacsimAdapter(std::shared_ptr<SENode> se_node);
51
52 void finish() final;
53};
Class that handles the communication between the SpeedEstimation node and the other nodes in the syst...
Definition adapter.hpp:21
Adapter class to interface with the Pacsim simulator for SLAM.
Definition pacsim.hpp:17
rclcpp::Subscription< pacsim::msg::PerceptionDetections >::SharedPtr _perception_detections_subscription_
Subscriber for simulated perception detections.
Definition pacsim.hpp:30
message_filters::Subscriber< pacsim::msg::Wheels > _pacsim_wheel_speeds_subscription_
Subscriber for wheel speeds.
Definition pacsim.hpp:19
message_filters::sync_policies::ApproximateTime< pacsim::msg::Wheels, pacsim::msg::StampedScalar > WheelSteerPolicy
Policy for synchronizing wheel speeds and steering angle.
Definition pacsim.hpp:25
std::shared_ptr< message_filters::Synchronizer< WheelSteerPolicy > > _sync_
Synchronizer for wheel speeds and steering angle.
Definition pacsim.hpp:27
void perception_detections_subscription_callback(const pacsim::msg::PerceptionDetections &msg)
Callback for simulated perception detections from pacsim.
Definition pacsim.cpp:49
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...
Definition pacsim.cpp:34
void finish() final
Function that sends the finish signal to the respective node.
Definition pacsim.cpp:41
rclcpp::Client< std_srvs::srv::Empty >::SharedPtr _finished_client_
Client for finished signal.
Definition pacsim.hpp:33
message_filters::Subscriber< pacsim::msg::StampedScalar > _steering_angle_subscription_
Subscriber for steering angle.
Definition pacsim.hpp:21
Class representing the main speed_est node responsible for publishing the calculated vehicle state wi...
Definition se_node.hpp:33