Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
PacSimAdapter Class Reference

Adapter for the PacSim simulator. More...

#include <pacsim.hpp>

Inheritance diagram for PacSimAdapter:
Inheritance graph
Collaboration diagram for PacSimAdapter:
Collaboration graph

Public Member Functions

 PacSimAdapter (const ControlParameters &params)
 
void _pacsim_gt_pose_callback (const geometry_msgs::msg::TwistWithCovarianceStamped &msg)
 Callback for the pacsim ground truth pose topic, used when using simulated SLAM.
 
void _pacsim_gt_velocities_callback (const geometry_msgs::msg::TwistWithCovarianceStamped &msg)
 Callback for the pacsim ground truth velocity topic, used when using simulated velocity estimation.
 
void _pacsim_gt_state_vector_callback (const custom_interfaces::msg::VehicleStateVector &msg)
 Callback for the pacsim ground truth state vector topic, used when using simulated full state estimation.
 
void publish_command (common_lib::structures::ControlCommand cmd) override
 Adapters override this function to publish control commands in their environment.
 
 PacSimAdapter (const PlanningParameters &params)
 
void set_mission_state ()
 
void track_callback (const visualization_msgs::msg::MarkerArray &msg)
 
void finish () override
 Called when planning mission is completed.
 
void timer_callback ()
 
- Public Member Functions inherited from ControlNode
 ControlNode (const ControlParameters &params)
 
- Public Member Functions inherited from Planning
 Planning (const PlanningParameters &params)
 Constructs a Planning node with the specified configuration parameters.
 
void set_mission (Mission mission)
 Sets the mission type for planning execution.
 

Private Attributes

rclcpp::Publisher< pacsim::msg::StampedScalar >::SharedPtr steering_pub_
 
rclcpp::Publisher< pacsim::msg::Wheels >::SharedPtr throttle_pub_
 
rclcpp::Subscription< geometry_msgs::msg::TwistWithCovarianceStamped >::SharedPtr car_velocity_sub_
 
rclcpp::Subscription< geometry_msgs::msg::TwistWithCovarianceStamped >::SharedPtr car_pose_sub_
 
rclcpp::Subscription< custom_interfaces::msg::VehicleStateVector >::SharedPtr car_state_vector_sub_
 
rclcpp::Client< std_srvs::srv::Empty >::SharedPtr finished_client_
 
rclcpp::Subscription< visualization_msgs::msg::MarkerArray >::SharedPtr path_sub_
 
rclcpp::TimerBase::SharedPtr timer_
 
std::unique_ptr< tf2_ros::Buffer > tf_buffer_
 
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
 

Additional Inherited Members

- Static Public Member Functions inherited from Planning
static PlanningParameters load_config (std::string &adapter)
 Loads planning configuration from YAML files.
 
- Protected Member Functions inherited from ControlNode
void vehicle_pose_callback (const custom_interfaces::msg::Pose &msg)
 Called when a new vehicle pose is received.
 
void path_callback (const custom_interfaces::msg::PathPointArray &msg)
 Called when a new path is received.
 
void vehicle_state_callback (const custom_interfaces::msg::Velocities &msg)
 Called when a new velocity is received.
 
- Protected Attributes inherited from ControlNode
bool go_signal_ {false}
 
ControlParameters params_
 

Detailed Description

Adapter for the PacSim simulator.

Works on a publish-subscribe model.

Definition at line 16 of file pacsim.hpp.

Constructor & Destructor Documentation

◆ PacSimAdapter() [1/2]

PacSimAdapter::PacSimAdapter ( const ControlParameters params)
explicit

Definition at line 3 of file pacsim.cpp.

Here is the call graph for this function:

◆ PacSimAdapter() [2/2]

PacSimAdapter::PacSimAdapter ( const PlanningParameters params)
explicit

Definition at line 3 of file pacsim.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ _pacsim_gt_pose_callback()

void PacSimAdapter::_pacsim_gt_pose_callback ( const geometry_msgs::msg::TwistWithCovarianceStamped &  msg)

Callback for the pacsim ground truth pose topic, used when using simulated SLAM.

Definition at line 28 of file pacsim.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _pacsim_gt_state_vector_callback()

void PacSimAdapter::_pacsim_gt_state_vector_callback ( const custom_interfaces::msg::VehicleStateVector &  msg)

Callback for the pacsim ground truth state vector topic, used when using simulated full state estimation.

Definition at line 49 of file pacsim.cpp.

Here is the caller graph for this function:

◆ _pacsim_gt_velocities_callback()

void PacSimAdapter::_pacsim_gt_velocities_callback ( const geometry_msgs::msg::TwistWithCovarianceStamped &  msg)

Callback for the pacsim ground truth velocity topic, used when using simulated velocity estimation.

Definition at line 39 of file pacsim.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ finish()

void PacSimAdapter::finish ( )
overridevirtual

Called when planning mission is completed.

Implements Planning.

Definition at line 47 of file pacsim.cpp.

◆ publish_command()

void PacSimAdapter::publish_command ( common_lib::structures::ControlCommand  cmd)
overridevirtual

Adapters override this function to publish control commands in their environment.

Parameters
cmdControl command to be published

Implements ControlNode.

Definition at line 54 of file pacsim.cpp.

◆ set_mission_state()

void PacSimAdapter::set_mission_state ( )

Definition at line 43 of file pacsim.cpp.

◆ timer_callback()

void PacSimAdapter::timer_callback ( )

Definition at line 20 of file pacsim.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ track_callback()

void PacSimAdapter::track_callback ( const visualization_msgs::msg::MarkerArray &  msg)

Definition at line 55 of file pacsim.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ car_pose_sub_

rclcpp::Subscription<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr PacSimAdapter::car_pose_sub_
private

Definition at line 24 of file pacsim.hpp.

◆ car_state_vector_sub_

rclcpp::Subscription<custom_interfaces::msg::VehicleStateVector>::SharedPtr PacSimAdapter::car_state_vector_sub_
private

Definition at line 25 of file pacsim.hpp.

◆ car_velocity_sub_

rclcpp::Subscription<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr PacSimAdapter::car_velocity_sub_
private

Definition at line 23 of file pacsim.hpp.

◆ finished_client_

rclcpp::Client<std_srvs::srv::Empty>::SharedPtr PacSimAdapter::finished_client_
private

Definition at line 21 of file pacsim.hpp.

◆ path_sub_

rclcpp::Subscription<visualization_msgs::msg::MarkerArray>::SharedPtr PacSimAdapter::path_sub_
private

Definition at line 22 of file pacsim.hpp.

◆ steering_pub_

rclcpp::Publisher<pacsim::msg::StampedScalar>::SharedPtr PacSimAdapter::steering_pub_
private

Definition at line 19 of file pacsim.hpp.

◆ tf_buffer_

std::unique_ptr<tf2_ros::Buffer> PacSimAdapter::tf_buffer_
private

Definition at line 25 of file pacsim.hpp.

◆ tf_listener_

std::shared_ptr<tf2_ros::TransformListener> PacSimAdapter::tf_listener_
private

Definition at line 26 of file pacsim.hpp.

◆ throttle_pub_

rclcpp::Publisher<pacsim::msg::Wheels>::SharedPtr PacSimAdapter::throttle_pub_
private

Definition at line 20 of file pacsim.hpp.

◆ timer_

rclcpp::TimerBase::SharedPtr PacSimAdapter::timer_
private

Definition at line 23 of file pacsim.hpp.


The documentation for this class was generated from the following files: