|
Formula Student Autonomous Systems
The code for the main driverless system
|
Class representing the main SLAM node responsible for publishing the calculated pose and map. More...
#include <slam_node.hpp>


Public Member Functions | |
| SLAMNode (const SLAMParameters ¶ms) | |
| Constructor that uses the parameters structure. | |
| void | init () |
| Initialize functions @description This method is used to initialize things that require the constructed node. | |
| virtual void | finish ()=0 |
| Finish the mission. | |
Protected Member Functions | |
| void | _perception_subscription_callback (const custom_interfaces::msg::PerceptionOutput &msg) |
| Callback that updates everytime information is received from the perception module. | |
| void | _velocities_subscription_callback (const custom_interfaces::msg::Velocities &msg) |
| Callback that updates everytime information is received from velocity estimation node. | |
| void | _imu_subscription_callback (const sensor_msgs::msg::Imu &msg) |
| Callback that updates everytime information is received from the IMU. | |
| void | _publish_vehicle_pose () |
| publishes the localization ('vehicle_pose') to the topic vehicle_pose | |
| void | _publish_map () |
| publishes the map ('track_map') to the topic track_map | |
| void | _publish_associations () |
| Publishes the visualization of the associations by data association. | |
| void | _publish_covariance () |
| publishes the covariance of the state | |
| void | _publish_lap_counter () |
| publishes the lap counter | |
| bool | _is_mission_finished () |
| Checks if the mission is finished. | |
Protected Attributes | |
| rclcpp::CallbackGroup::SharedPtr | _callback_group_ |
| Callback group for subscriptions, used to control if they are concurrent or not. | |
| rclcpp::Subscription< custom_interfaces::msg::PerceptionOutput >::SharedPtr | _perception_subscription_ |
| rclcpp::Subscription< custom_interfaces::msg::Velocities >::SharedPtr | _velocities_subscription_ |
| rclcpp::Publisher< custom_interfaces::msg::Pose >::SharedPtr | _vehicle_pose_publisher_ |
| rclcpp::Publisher< custom_interfaces::msg::ConeArray >::SharedPtr | _map_publisher_ |
| rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr | _visualization_map_publisher_ |
| rclcpp::Publisher< visualization_msgs::msg::Marker >::SharedPtr | _position_visualization_publisher_ |
| Publishes the vehicle position. | |
| rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr | _trajectory_visualization_publisher_ |
| Publishes full vehicle trajectory. | |
| rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr | _associations_visualization_publisher_ |
| rclcpp::Publisher< std_msgs::msg::Float64MultiArray >::SharedPtr | _execution_time_publisher_ |
| rclcpp::Publisher< std_msgs::msg::Float64MultiArray >::SharedPtr | _covariance_publisher_ |
| Publishes the covariance of the pose. | |
| rclcpp::Publisher< std_msgs::msg::Float64 >::SharedPtr | _lap_counter_publisher_ |
| rclcpp::Publisher< std_msgs::msg::Float64 >::SharedPtr | _perception_delta_publisher_ |
| rclcpp::Time | _last_perception_message_time_ = rclcpp::Time(0) |
| rclcpp::CallbackGroup::SharedPtr | _parallel_callback_group_ |
| std::shared_mutex | mutex_ |
| std::shared_ptr< tf2_ros::TransformBroadcaster > | _tf_broadcaster_ |
| rclcpp::TimerBase::SharedPtr | _timer_ |
| timer | |
| std::shared_ptr< SLAMSolver > | _slam_solver_ |
| SLAM solver object. | |
| std::vector< common_lib::structures::Cone > | _perception_map_ |
| common_lib::structures::Velocities | _vehicle_state_velocities_ |
| std::vector< common_lib::structures::Cone > | _track_map_ |
| Eigen::VectorXi | _associations_ |
| Eigen::VectorXd | _observations_global_ |
| Global observations of the cones. | |
| Eigen::VectorXd | _map_coordinates_ |
| Coordinates of the cones in the map. | |
| common_lib::structures::Pose | _vehicle_pose_ |
| std::shared_ptr< std::vector< double > > | _execution_times_ |
| common_lib::competition_logic::Mission | _mission_ = common_lib::competition_logic::Mission::NONE |
| bool | _go_ = true |
| std::string | _adapter_name_ |
| flag to start the mission | |
| std::string | _vehicle_frame_id_ |
| Frame id of the vehicle for the transform. | |
| SLAMParameters | _params_ |
Class representing the main SLAM node responsible for publishing the calculated pose and map.
Definition at line 35 of file slam_node.hpp.
| SLAMNode::SLAMNode | ( | const SLAMParameters & | params | ) |
Constructor that uses the parameters structure.
Definition at line 21 of file slam_node.cpp.

|
protected |
Callback that updates everytime information is received from the IMU.
| msg | Message containing the IMU data |
Definition at line 261 of file slam_node.cpp.

|
protected |
Checks if the mission is finished.
Definition at line 436 of file slam_node.cpp.

|
protected |
Callback that updates everytime information is received from the perception module.
| msg | Message containing the array of perceived cones |
Definition at line 117 of file slam_node.cpp.


|
protected |
Publishes the visualization of the associations by data association.
Definition at line 382 of file slam_node.cpp.

|
protected |
publishes the covariance of the state
Definition at line 354 of file slam_node.cpp.
|
protected |
publishes the lap counter
Definition at line 376 of file slam_node.cpp.

|
protected |
publishes the map ('track_map') to the topic track_map
Definition at line 327 of file slam_node.cpp.


|
protected |
publishes the localization ('vehicle_pose') to the topic vehicle_pose
Definition at line 280 of file slam_node.cpp.


|
protected |
Callback that updates everytime information is received from velocity estimation node.
| msg | Message containing the velocities of the vehicle |
Definition at line 220 of file slam_node.cpp.


|
pure virtual |
Finish the mission.
Implemented in PacsimAdapter, VehicleAdapter, VehicleAdapter, PacsimAdapter, and VehicleAdapter.

| void SLAMNode::init | ( | ) |
Initialize functions @description This method is used to initialize things that require the constructed node.
Definition at line 109 of file slam_node.cpp.
|
protected |
flag to start the mission
Definition at line 78 of file slam_node.hpp.
|
protected |
Definition at line 69 of file slam_node.hpp.
|
protected |
Definition at line 50 of file slam_node.hpp.
|
protected |
Callback group for subscriptions, used to control if they are concurrent or not.
Definition at line 37 of file slam_node.hpp.
|
protected |
Publishes the covariance of the pose.
Definition at line 53 of file slam_node.hpp.
|
protected |
Definition at line 51 of file slam_node.hpp.
|
protected |
Definition at line 74 of file slam_node.hpp.
|
protected |
Definition at line 77 of file slam_node.hpp.
|
protected |
Definition at line 55 of file slam_node.hpp.
|
protected |
Definition at line 57 of file slam_node.hpp.
|
protected |
Coordinates of the cones in the map.
Definition at line 71 of file slam_node.hpp.
|
protected |
Definition at line 43 of file slam_node.hpp.
|
protected |
Definition at line 76 of file slam_node.hpp.
|
protected |
Global observations of the cones.
Definition at line 70 of file slam_node.hpp.
|
protected |
Definition at line 59 of file slam_node.hpp.
|
protected |
Definition at line 80 of file slam_node.hpp.
|
protected |
Definition at line 56 of file slam_node.hpp.
|
protected |
Definition at line 66 of file slam_node.hpp.
|
protected |
Definition at line 40 of file slam_node.hpp.
|
protected |
Publishes the vehicle position.
Definition at line 46 of file slam_node.hpp.
|
protected |
SLAM solver object.
Definition at line 65 of file slam_node.hpp.
|
protected |
Definition at line 63 of file slam_node.hpp.
|
protected |
timer
Definition at line 64 of file slam_node.hpp.
|
protected |
Definition at line 68 of file slam_node.hpp.
|
protected |
Publishes full vehicle trajectory.
Definition at line 48 of file slam_node.hpp.
|
protected |
Frame id of the vehicle for the transform.
Definition at line 79 of file slam_node.hpp.
|
protected |
Definition at line 72 of file slam_node.hpp.
|
protected |
Definition at line 42 of file slam_node.hpp.
|
protected |
Definition at line 67 of file slam_node.hpp.
|
protected |
Definition at line 41 of file slam_node.hpp.
|
protected |
Definition at line 44 of file slam_node.hpp.
|
protected |
Definition at line 61 of file slam_node.hpp.