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 <tf2/LinearMath/Matrix3x3.h>
4#include <tf2/LinearMath/Quaternion.h>
5
6#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
7#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
8
9#include "custom_interfaces/msg/vehicle_state.hpp"
10#include "geometry_msgs/msg/transform_stamped.hpp"
11#include "pacsim/msg/stamped_scalar.hpp"
12#include "planning/planning.hpp"
13#include "sensor_msgs/msg/joint_state.hpp"
14#include "std_srvs/srv/empty.hpp"
15#include "std_srvs/srv/trigger.hpp"
16#include "tf2_ros/buffer.h"
17#include "tf2_ros/transform_listener.h"
18#include "visualization_msgs/msg/marker_array.hpp"
19
20class PacSimAdapter : public Planning {
21 rclcpp::Client<std_srvs::srv::Empty>::SharedPtr finished_client_;
22 rclcpp::Subscription<visualization_msgs::msg::MarkerArray>::SharedPtr path_sub_;
23 rclcpp::TimerBase::SharedPtr timer_;
24
25 std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
26 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
27
28public:
29 explicit PacSimAdapter(const PlanningParameters& params);
30
31 void set_mission_state();
32 void track_callback(const visualization_msgs::msg::MarkerArray& msg);
33 void finish() override;
34 void timer_callback();
35};
Adapter for the PacSim simulator.
Definition pacsim.hpp:16
void finish() override
Called when planning mission is completed.
Definition pacsim.cpp:47
void timer_callback()
Definition pacsim.cpp:20
void set_mission_state()
Definition pacsim.cpp:43
rclcpp::TimerBase::SharedPtr timer_
Definition pacsim.hpp:23
void track_callback(const visualization_msgs::msg::MarkerArray &msg)
Definition pacsim.cpp:55
rclcpp::Subscription< visualization_msgs::msg::MarkerArray >::SharedPtr path_sub_
Definition pacsim.hpp:22
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
Definition pacsim.hpp:26
std::unique_ptr< tf2_ros::Buffer > tf_buffer_
Definition pacsim.hpp:25
rclcpp::Client< std_srvs::srv::Empty >::SharedPtr finished_client_
Definition pacsim.hpp:21
Responsible for path planning and trajectory generation for the autonomous vehicle.
Definition planning.hpp:54
friend class PacSimAdapter
Definition planning.hpp:85