3#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
4#include <std_srvs/srv/empty.hpp>
7#include "pacsim/msg/perception_detections.hpp"
17 rclcpp::Subscription<pacsim::msg::PerceptionDetections>::SharedPtr
20 rclcpp::Subscription<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr
23 rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr
26 rclcpp::Client<std_srvs::srv::Empty>::SharedPtr
29 rclcpp::Client<rcl_interfaces::srv::GetParameters>::SharedPtr
param_client_;
44 const geometry_msgs::msg::TwistWithCovarianceStamped& msg);
Adapter class to interface with the Pacsim simulator for SLAM.
rclcpp::Subscription< geometry_msgs::msg::TwistWithCovarianceStamped >::SharedPtr _velocities_subscription_
Subscriber for simulated velocities.
void _pacsim_imu_subscription_callback(const sensor_msgs::msg::Imu &msg)
Callback for simulated IMU data from pacsim.
rclcpp::Subscription< pacsim::msg::PerceptionDetections >::SharedPtr _perception_detections_subscription_
Subscriber for simulated perception detections.
void fetch_discipline()
Fetches the mission from the parameters.
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.
void _pacsim_perception_subscription_callback(const pacsim::msg::PerceptionDetections &msg)
Callback for simulated perception detections from pacsim.
void _pacsim_velocities_subscription_callback(const geometry_msgs::msg::TwistWithCovarianceStamped &msg)
Callback for simulated velocities from pacsim.
rclcpp::Client< rcl_interfaces::srv::GetParameters >::SharedPtr param_client_
rclcpp::Client< std_srvs::srv::Empty >::SharedPtr _finished_client_
Client for finished signal.
Class representing the main SLAM node responsible for publishing the calculated pose and map.
Parameters for the SLAM node.