Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
vehicle.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <nav_msgs/msg/odometry.hpp>
4
5#include "custom_interfaces/msg/operational_status.hpp"
7#include "std_srvs/srv/empty.hpp"
8#include "std_srvs/srv/trigger.hpp"
9#include "tf2_ros/static_transform_broadcaster.h"
10
17class VehicleAdapter : public SLAMNode {
18 rclcpp::Subscription<custom_interfaces::msg::OperationalStatus>::SharedPtr
20 rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr _lidar_odometry_subscription_;
21
22 rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr
24
25 std::shared_ptr<tf2_ros::StaticTransformBroadcaster>
27
28public:
32 VehicleAdapter(const SLAMParameters& params);
33
39 void _lidar_odometry_subscription_callback(const nav_msgs::msg::Odometry& msg);
40
44 void finish() override;
45};
friend class VehicleAdapter
Definition planning.hpp:88
Class representing the main SLAM node responsible for publishing the calculated pose and map.
Definition slam_node.hpp:35
Adapter for interfacing with the real vehicle hardware.
Definition vehicle.hpp:15
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr _lidar_odometry_subscription_
Definition vehicle.hpp:20
rclcpp::Client< std_srvs::srv::Trigger >::SharedPtr _finished_client_
Client for finished signal.
Definition vehicle.hpp:53
std::shared_ptr< tf2_ros::StaticTransformBroadcaster > _tf_static_broadcaster_
Static transform broadcaster.
Definition vehicle.hpp:26
rclcpp::Subscription< custom_interfaces::msg::OperationalStatus >::SharedPtr _operational_status_subscription_
Subscriber for operational status.
Definition vehicle.hpp:27
void finish() override
Sends the finished signal to the vehicle control.
void _lidar_odometry_subscription_callback(const nav_msgs::msg::Odometry &msg)
LiDAR odometry subscription callback.
Definition vehicle.cpp:77
Parameters for the SLAM node.