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 <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
4#include <std_srvs/srv/empty.hpp>
5
7#include "pacsim/msg/perception_detections.hpp"
9
16class PacsimAdapter : public SLAMNode {
17 rclcpp::Subscription<pacsim::msg::PerceptionDetections>::SharedPtr
19
20 rclcpp::Subscription<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr
22
23 rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr
25
26 rclcpp::Client<std_srvs::srv::Empty>::SharedPtr
28
29 rclcpp::Client<rcl_interfaces::srv::GetParameters>::SharedPtr param_client_; // for mission logic
30
36 void _pacsim_perception_subscription_callback(const pacsim::msg::PerceptionDetections& msg);
37
44 const geometry_msgs::msg::TwistWithCovarianceStamped& msg);
45
50 void _pacsim_imu_subscription_callback(const sensor_msgs::msg::Imu& msg);
51
55 void fetch_discipline();
56
57public:
61 PacsimAdapter(const SLAMParameters& params);
62
63 void finish() override;
64};
Adapter class to interface with the Pacsim simulator for SLAM.
Definition pacsim.hpp:17
rclcpp::Subscription< geometry_msgs::msg::TwistWithCovarianceStamped >::SharedPtr _velocities_subscription_
Subscriber for simulated velocities.
Definition pacsim.hpp:21
void _pacsim_imu_subscription_callback(const sensor_msgs::msg::Imu &msg)
Callback for simulated IMU data from pacsim.
Definition pacsim.cpp:135
rclcpp::Subscription< pacsim::msg::PerceptionDetections >::SharedPtr _perception_detections_subscription_
Subscriber for simulated perception detections.
Definition pacsim.hpp:30
void fetch_discipline()
Fetches the mission from the parameters.
Definition pacsim.cpp:57
void finish() override
Function that sends the finish signal to the respective node.
rclcpp::Subscription< sensor_msgs::msg::Imu >::SharedPtr _imu_subscription_
Subscriber for simulated IMU data.
Definition pacsim.hpp:24
void _pacsim_perception_subscription_callback(const pacsim::msg::PerceptionDetections &msg)
Callback for simulated perception detections from pacsim.
Definition pacsim.cpp:98
void _pacsim_velocities_subscription_callback(const geometry_msgs::msg::TwistWithCovarianceStamped &msg)
Callback for simulated velocities from pacsim.
Definition pacsim.cpp:120
rclcpp::Client< rcl_interfaces::srv::GetParameters >::SharedPtr param_client_
Definition pacsim.hpp:29
rclcpp::Client< std_srvs::srv::Empty >::SharedPtr _finished_client_
Client for finished signal.
Definition pacsim.hpp:33
Class representing the main SLAM node responsible for publishing the calculated pose and map.
Definition slam_node.hpp:35
Parameters for the SLAM node.