Adapter for the PacSim simulator.
More...
#include <pacsim.hpp>
|
| 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_ |
| |
Adapter for the PacSim simulator.
Works on a publish-subscribe model.
Definition at line 16 of file pacsim.hpp.
◆ PacSimAdapter() [1/2]
◆ PacSimAdapter() [2/2]
◆ _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.
◆ _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.
◆ _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.
◆ finish()
| void PacSimAdapter::finish |
( |
| ) |
|
|
overridevirtual |
Called when planning mission is completed.
Implements Planning.
Definition at line 47 of file pacsim.cpp.
◆ publish_command()
Adapters override this function to publish control commands in their environment.
- Parameters
-
| cmd | Control command to be published |
Implements ControlNode.
Definition at line 54 of file pacsim.cpp.
◆ set_mission_state()
| void PacSimAdapter::set_mission_state |
( |
| ) |
|
◆ timer_callback()
| void PacSimAdapter::timer_callback |
( |
| ) |
|
◆ track_callback()
| void PacSimAdapter::track_callback |
( |
const visualization_msgs::msg::MarkerArray & |
msg | ) |
|
◆ car_pose_sub_
| rclcpp::Subscription<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr PacSimAdapter::car_pose_sub_ |
|
private |
◆ car_state_vector_sub_
| rclcpp::Subscription<custom_interfaces::msg::VehicleStateVector>::SharedPtr PacSimAdapter::car_state_vector_sub_ |
|
private |
◆ car_velocity_sub_
| rclcpp::Subscription<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr PacSimAdapter::car_velocity_sub_ |
|
private |
◆ finished_client_
| rclcpp::Client<std_srvs::srv::Empty>::SharedPtr PacSimAdapter::finished_client_ |
|
private |
◆ path_sub_
| rclcpp::Subscription<visualization_msgs::msg::MarkerArray>::SharedPtr PacSimAdapter::path_sub_ |
|
private |
◆ steering_pub_
| rclcpp::Publisher<pacsim::msg::StampedScalar>::SharedPtr PacSimAdapter::steering_pub_ |
|
private |
◆ tf_buffer_
| std::unique_ptr<tf2_ros::Buffer> PacSimAdapter::tf_buffer_ |
|
private |
◆ tf_listener_
| std::shared_ptr<tf2_ros::TransformListener> PacSimAdapter::tf_listener_ |
|
private |
◆ throttle_pub_
| rclcpp::Publisher<pacsim::msg::Wheels>::SharedPtr PacSimAdapter::throttle_pub_ |
|
private |
◆ timer_
| rclcpp::TimerBase::SharedPtr PacSimAdapter::timer_ |
|
private |
The documentation for this class was generated from the following files: