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

A ROS2 node for computing and publishing the system's real-time metrics. More...

Inheritance diagram for evaluator.evaluator.Evaluator:
Inheritance graph
Collaboration diagram for evaluator.evaluator.Evaluator:
Collaboration graph

Public Member Functions

None __init__ (self)
 
 get_config_yaml_path (self, package_name, dir, filename)
 
 load_config (self)
 
None signal_handler (self, int sig, frame)
 Writes metrics to csv and exits when Ctrl+C is pressed.
 
None metrics_to_csv (self, list metrics, str filename)
 
None correction_step_time_callback (self, Float64 msg)
 Callback function to store the execution time of the correction step.
 
None prediction_step_time_callback (self, Float64 msg)
 
None perception_execution_time_callback (self, Float64 msg)
 Callback function to store the perception execution time.
 
None planning_execution_time_callback (self, Float64 msg)
 Callback function to store the planning execution time.
 
None compute_and_publish_pose (self, np.ndarray pose, np.ndarray groundtruth_pose)
 Computes state estimation metrics and publishes them.
 
None compute_and_publish_map (self, np.ndarray map, np.ndarray groundtruth_map)
 Computes state estimation metrics and publishes them.
 
None compute_and_publish_velocities (self, np.ndarray velocities, np.ndarray groundtruth_velocities)
 Computes state estimation metrics and publishes them.
 
None compute_and_publish_perception (self, np.ndarray perception_output, np.ndarray perception_ground_truth)
 Computes perception metrics and publishes them.
 
 compute_and_publish_planning (self, np.ndarray path, np.ndarray path_gt, np.ndarray left_cones_gt, np.ndarray right_cones_gt)
 Computes planning metrics and publishes them.
 
 compute_and_publish_control (self, Float64 msg)
 Computes control metrics and publishes them.
 

Public Attributes

 perception_subscription_
 
 map_subscription_
 
 velocities_subscription_
 
 vehicle_pose_subscription_
 
 planning_subscription_
 
 transform_buffer_
 
 planning_gt_subscription_
 
 correction_step_time_callback
 
 prediction_step_time_callback
 
 planning_execution_time_callback
 
 perception_execution_time_callback
 
 compute_and_publish_control
 
 path_points
 
 position
 
 absolute_velocity
 
 csv_suffix
 
 perception_metrics
 
 map_metrics
 
 pose_metrics
 
 vel_estimation_metrics
 
 planning_metrics
 
 control_metrics
 
 signal_handler
 
 use_simulated_perception_
 
 use_simulated_se_
 
 use_simulated_velocities_
 
 use_simulated_planning_
 
 generate_csv
 

Protected Attributes

 _adapter_name_
 
 _transforms_listener_
 
 _correction_step_time_subscription_
 
 _prediction_step_time_subscription_
 
 _planning_execution_time_subscription_
 
 _perception_execution_time_subscription_
 
 _control_execution_time_subscription_
 
 _perception_mean_difference_
 
 _perception_mean_squared_difference_
 
 _perception_root_mean_squared_difference_
 
 _perception_inter_cones_distance_
 
 _perception_false_positives_
 
 _perception_precision_
 
 _perception_recall_
 
 _perception_number_duplicates
 
 _velocities_difference_
 
 _vehicle_pose_difference_
 
 _map_mean_squared_difference_
 
 _map_mean_difference_
 
 _map_root_mean_squared_difference_
 
 _se_false_positives_
 
 _se_number_duplicates
 
 _se_difference_with_map_
 
 _planning_mean_difference_to_gt
 
 _planning_mean_squared_difference_to_gt
 
 _planning_root_mean_squared_difference_to_gt
 
 _planning_mean_difference_to_left_cones
 
 _planning_mean_squared_difference_to_left_cones
 
 _planning_root_mean_squared_difference_to_left_cones
 
 _planning_mean_difference_to_right_cones
 
 _planning_mean_squared_difference_to_right_cones
 
 _planning_root_mean_squared_difference_to_right_cones
 
 _planning_mean_difference_to_cones
 
 _planning_mean_squared_difference_to_cones
 
 _planning_root_mean_squared_difference_to_cones
 
 _control_position_error_
 
 _control_velocity_error_
 
 _se_correction_execution_time_
 
 _se_prediction_execution_time_
 
 _control_execution_time_
 
 _planning_execution_time_
 
 _perception_execution_time_
 
 _control_position_error_sum
 
 _control_position_squared_error_sum
 
 _control_count
 
 _control_velocity_error_sum
 
 _control_velocity_squared_error_sum
 
 _perception_sum_error
 
 _perception_squared_sum_error
 
 _perception_root_squared_sum_error
 
 _perception_precision_sum
 
 _perception_recall_sum
 
 _perception_count
 
 _se_map_sum_error
 
 _se_map_squared_sum_error
 
 _se_map_mean_root_squared_sum_error
 
 _map_count_
 
 _pose_count_
 
 _ve_count_
 
 _sum_velocities_error
 
 _sum_squared_velocities_error
 
 _sum_vehicle_pose_error
 
 _sum_squared_vehicle_pose_error
 
 _planning_sum_error
 
 _planning_squared_sum_error
 
 _planning_mean_root_squared_sum_error
 
 _planning_count
 
 _perception_mean_mean_error
 
 _perception_mean_mean_squared_error
 
 _perception_mean_mean_root_squared_error
 
 _perception_mean_precision
 
 _perception_mean_recall
 
 _map_mean_mean_error
 
 _map_mean_mean_squared_error
 
 _map_mean_mean_root_squared_error
 
 _state_estimation_mean_vehicle_pose_error
 
 _state_estimation_mean_squared_vehicle_pose_error
 
 _state_estimation_root_mean_squared_vehicle_pose_error
 
 _state_estimation_mean_velocities_error
 
 _state_estimation_mean_squared_velocities_error
 
 _state_estimation_root_mean_squared_velocities_error
 
 _planning_mean_mean_error
 
 _planning_mean_mean_squared_error
 
 _planning_mean_mean_root_squared_error
 
 _control_position_mean_error_
 
 _control_position_mean_squared_error_
 
 _control_position_root_mean_squared_error_
 
 _control_velocity_mean_error_
 
 _control_velocity_mean_squared_error_
 
 _control_velocity_root_mean_squared_error_
 

Detailed Description

A ROS2 node for computing and publishing the system's real-time metrics.

Definition at line 56 of file evaluator.py.

Constructor & Destructor Documentation

◆ __init__()

None evaluator.evaluator.Evaluator.__init__ (   self)
Initializes the Evaluator Node.
This function sets up the necessary parameters, subscriptions, and publishers for the Evaluator Node.
It also initializes variables for storing metrics over time.
Parameters:
    None
Returns:
    None

Definition at line 61 of file evaluator.py.

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

Member Function Documentation

◆ compute_and_publish_control()

evaluator.evaluator.Evaluator.compute_and_publish_control (   self,
Float64  msg 
)

Computes control metrics and publishes them.

Args: msg (Float64): Control execution time message.

Definition at line 1247 of file evaluator.py.

◆ compute_and_publish_map()

None evaluator.evaluator.Evaluator.compute_and_publish_map (   self,
np.ndarray  map,
np.ndarray  groundtruth_map 
)

Computes state estimation metrics and publishes them.

Args: pose (np.ndarray): Vehicle state estimation data. [x,y,theta] groundtruth_pose (np.ndarray): Ground truth vehicle state data. [x,y,theta] map (np.ndarray): Map data. [[x,y,color,confidence]] groundtruth_map (np.ndarray): Ground truth map data. [[x,y,color,confidence]]

Definition at line 719 of file evaluator.py.

◆ compute_and_publish_perception()

None evaluator.evaluator.Evaluator.compute_and_publish_perception (   self,
np.ndarray  perception_output,
np.ndarray   perception_ground_truth 
)

Computes perception metrics and publishes them.

Args: perception_output (np.ndarray): Perceived cones. perception_ground_truth (np.ndarray): Ground truth cones.

Definition at line 922 of file evaluator.py.

◆ compute_and_publish_planning()

evaluator.evaluator.Evaluator.compute_and_publish_planning (   self,
np.ndarray  path,
np.ndarray  path_gt,
np.ndarray  left_cones_gt,
np.ndarray  right_cones_gt 
)

Computes planning metrics and publishes them.

Args: path (np.ndarray): Path computed by the planner. left_cones_gt (np.ndarray): Ground truth of the left cones. right_cones_gt (np.ndarray): Ground truth of the right cones.

Definition at line 1072 of file evaluator.py.

◆ compute_and_publish_pose()

None evaluator.evaluator.Evaluator.compute_and_publish_pose (   self,
np.ndarray  pose,
np.ndarray  groundtruth_pose 
)

Computes state estimation metrics and publishes them.

Args: pose (np.ndarray): Vehicle state estimation data. [x,y,theta] groundtruth_pose (np.ndarray): Ground truth vehicle state data. [x,y,theta]

Definition at line 614 of file evaluator.py.

◆ compute_and_publish_velocities()

None evaluator.evaluator.Evaluator.compute_and_publish_velocities (   self,
np.ndarray  velocities,
np.ndarray  groundtruth_velocities 
)

Computes state estimation metrics and publishes them.

Args: velocities (np.ndarray): Vehicle state velocities. [vx, vy, w] groundtruth_velocities (np.ndarray): Ground truth vehicle state velocities. [vx, vy, w]

Definition at line 826 of file evaluator.py.

◆ correction_step_time_callback()

None evaluator.evaluator.Evaluator.correction_step_time_callback (   self,
Float64  msg 
)

Callback function to store the execution time of the correction step.

Args: msg (Float64): Message containing the correction step execution time. Returns: None

Definition at line 563 of file evaluator.py.

◆ get_config_yaml_path()

evaluator.evaluator.Evaluator.get_config_yaml_path (   self,
  package_name,
  dir,
  filename 
)

Definition at line 460 of file evaluator.py.

Here is the caller graph for this function:

◆ load_config()

evaluator.evaluator.Evaluator.load_config (   self)
Load configuration from YAML file.

Definition at line 467 of file evaluator.py.

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

◆ metrics_to_csv()

None evaluator.evaluator.Evaluator.metrics_to_csv (   self,
list  metrics,
str  filename 
)
Converts metrics to csv and writes them to a file.
Args:
    metrics (list): A list of dictionaries representing the metrics.
    filename (str): The name of the CSV file to write the metrics to.
Returns:
    None

Definition at line 540 of file evaluator.py.

Here is the caller graph for this function:

◆ perception_execution_time_callback()

None evaluator.evaluator.Evaluator.perception_execution_time_callback (   self,
Float64  msg 
)

Callback function to store the perception execution time.

Args: msg (Float64): Message containing the Perception execution time. Returns: None

Definition at line 588 of file evaluator.py.

◆ planning_execution_time_callback()

None evaluator.evaluator.Evaluator.planning_execution_time_callback (   self,
Float64  msg 
)

Callback function to store the planning execution time.

Args: msg (Float64): Message containing the planning execution time. Returns: None

Definition at line 601 of file evaluator.py.

◆ prediction_step_time_callback()

None evaluator.evaluator.Evaluator.prediction_step_time_callback (   self,
Float64  msg 
)
Callback function to store the execution time of the prediction step.
Args:
    msg (Float64): Message containing the prediction step execution time.
Returns:
    None

Definition at line 576 of file evaluator.py.

◆ signal_handler()

None evaluator.evaluator.Evaluator.signal_handler (   self,
int  sig,
  frame 
)

Writes metrics to csv and exits when Ctrl+C is pressed.

This function is triggered when the program receives a termination signal (e.g., SIGINT or SIGTERM) and it saves the collected metrics to CSV files, then exits the program with a status code of 0. The metrics are saved in separate CSV files based on their category.

Args: sig (int): The signal number. (not used in this function) frame (frame): The current stack frame. (not used in this function) Note:

  • Metrics are saved in the "performance/evaluator_metrics" directory as "<metric_name>_<timestamp>.csv".
  • If a category has no metrics, no CSV file will be created for that category. Example:

Create an instance of the Evaluator class

evaluator = Evaluator()

Register the signal handler function

signal.signal(signal.SIGINT, evaluator.signal_handler)

Start the program

evaluator.run()

Definition at line 497 of file evaluator.py.

Here is the call graph for this function:

Member Data Documentation

◆ _adapter_name_

evaluator.evaluator.Evaluator._adapter_name_
protected

Definition at line 77 of file evaluator.py.

◆ _control_count

evaluator.evaluator.Evaluator._control_count
protected

Definition at line 300 of file evaluator.py.

◆ _control_execution_time_

evaluator.evaluator.Evaluator._control_execution_time_
protected

Definition at line 294 of file evaluator.py.

◆ _control_execution_time_subscription_

evaluator.evaluator.Evaluator._control_execution_time_subscription_
protected

Definition at line 165 of file evaluator.py.

◆ _control_position_error_

evaluator.evaluator.Evaluator._control_position_error_
protected

Definition at line 275 of file evaluator.py.

◆ _control_position_error_sum

evaluator.evaluator.Evaluator._control_position_error_sum
protected

Definition at line 298 of file evaluator.py.

◆ _control_position_mean_error_

evaluator.evaluator.Evaluator._control_position_mean_error_
protected

Definition at line 429 of file evaluator.py.

◆ _control_position_mean_squared_error_

evaluator.evaluator.Evaluator._control_position_mean_squared_error_
protected

Definition at line 432 of file evaluator.py.

◆ _control_position_root_mean_squared_error_

evaluator.evaluator.Evaluator._control_position_root_mean_squared_error_
protected

Definition at line 435 of file evaluator.py.

◆ _control_position_squared_error_sum

evaluator.evaluator.Evaluator._control_position_squared_error_sum
protected

Definition at line 299 of file evaluator.py.

◆ _control_velocity_error_

evaluator.evaluator.Evaluator._control_velocity_error_
protected

Definition at line 278 of file evaluator.py.

◆ _control_velocity_error_sum

evaluator.evaluator.Evaluator._control_velocity_error_sum
protected

Definition at line 301 of file evaluator.py.

◆ _control_velocity_mean_error_

evaluator.evaluator.Evaluator._control_velocity_mean_error_
protected

Definition at line 439 of file evaluator.py.

◆ _control_velocity_mean_squared_error_

evaluator.evaluator.Evaluator._control_velocity_mean_squared_error_
protected

Definition at line 442 of file evaluator.py.

◆ _control_velocity_root_mean_squared_error_

evaluator.evaluator.Evaluator._control_velocity_root_mean_squared_error_
protected

Definition at line 447 of file evaluator.py.

◆ _control_velocity_squared_error_sum

evaluator.evaluator.Evaluator._control_velocity_squared_error_sum
protected

Definition at line 302 of file evaluator.py.

◆ _correction_step_time_subscription_

evaluator.evaluator.Evaluator._correction_step_time_subscription_
protected

Definition at line 141 of file evaluator.py.

◆ _map_count_

evaluator.evaluator.Evaluator._map_count_
protected

Definition at line 314 of file evaluator.py.

◆ _map_mean_difference_

evaluator.evaluator.Evaluator._map_mean_difference_
protected

Definition at line 216 of file evaluator.py.

◆ _map_mean_mean_error

evaluator.evaluator.Evaluator._map_mean_mean_error
protected

Definition at line 361 of file evaluator.py.

◆ _map_mean_mean_root_squared_error

evaluator.evaluator.Evaluator._map_mean_mean_root_squared_error
protected

Definition at line 369 of file evaluator.py.

◆ _map_mean_mean_squared_error

evaluator.evaluator.Evaluator._map_mean_mean_squared_error
protected

Definition at line 365 of file evaluator.py.

◆ _map_mean_squared_difference_

evaluator.evaluator.Evaluator._map_mean_squared_difference_
protected

Definition at line 213 of file evaluator.py.

◆ _map_root_mean_squared_difference_

evaluator.evaluator.Evaluator._map_root_mean_squared_difference_
protected

Definition at line 219 of file evaluator.py.

◆ _perception_count

evaluator.evaluator.Evaluator._perception_count
protected

Definition at line 309 of file evaluator.py.

◆ _perception_execution_time_

evaluator.evaluator.Evaluator._perception_execution_time_
protected

Definition at line 296 of file evaluator.py.

◆ _perception_execution_time_subscription_

evaluator.evaluator.Evaluator._perception_execution_time_subscription_
protected

Definition at line 159 of file evaluator.py.

◆ _perception_false_positives_

evaluator.evaluator.Evaluator._perception_false_positives_
protected

Definition at line 189 of file evaluator.py.

◆ _perception_inter_cones_distance_

evaluator.evaluator.Evaluator._perception_inter_cones_distance_
protected

Definition at line 186 of file evaluator.py.

◆ _perception_mean_difference_

evaluator.evaluator.Evaluator._perception_mean_difference_
protected

Definition at line 177 of file evaluator.py.

◆ _perception_mean_mean_error

evaluator.evaluator.Evaluator._perception_mean_mean_error
protected

Definition at line 340 of file evaluator.py.

◆ _perception_mean_mean_root_squared_error

evaluator.evaluator.Evaluator._perception_mean_mean_root_squared_error
protected

Definition at line 348 of file evaluator.py.

◆ _perception_mean_mean_squared_error

evaluator.evaluator.Evaluator._perception_mean_mean_squared_error
protected

Definition at line 344 of file evaluator.py.

◆ _perception_mean_precision

evaluator.evaluator.Evaluator._perception_mean_precision
protected

Definition at line 352 of file evaluator.py.

◆ _perception_mean_recall

evaluator.evaluator.Evaluator._perception_mean_recall
protected

Definition at line 356 of file evaluator.py.

◆ _perception_mean_squared_difference_

evaluator.evaluator.Evaluator._perception_mean_squared_difference_
protected

Definition at line 180 of file evaluator.py.

◆ _perception_number_duplicates

evaluator.evaluator.Evaluator._perception_number_duplicates
protected

Definition at line 198 of file evaluator.py.

◆ _perception_precision_

evaluator.evaluator.Evaluator._perception_precision_
protected

Definition at line 192 of file evaluator.py.

◆ _perception_precision_sum

evaluator.evaluator.Evaluator._perception_precision_sum
protected

Definition at line 307 of file evaluator.py.

◆ _perception_recall_

evaluator.evaluator.Evaluator._perception_recall_
protected

Definition at line 195 of file evaluator.py.

◆ _perception_recall_sum

evaluator.evaluator.Evaluator._perception_recall_sum
protected

Definition at line 308 of file evaluator.py.

◆ _perception_root_mean_squared_difference_

evaluator.evaluator.Evaluator._perception_root_mean_squared_difference_
protected

Definition at line 183 of file evaluator.py.

◆ _perception_root_squared_sum_error

evaluator.evaluator.Evaluator._perception_root_squared_sum_error
protected

Definition at line 306 of file evaluator.py.

◆ _perception_squared_sum_error

evaluator.evaluator.Evaluator._perception_squared_sum_error
protected

Definition at line 305 of file evaluator.py.

◆ _perception_sum_error

evaluator.evaluator.Evaluator._perception_sum_error
protected

Definition at line 304 of file evaluator.py.

◆ _planning_count

evaluator.evaluator.Evaluator._planning_count
protected

Definition at line 337 of file evaluator.py.

◆ _planning_execution_time_

evaluator.evaluator.Evaluator._planning_execution_time_
protected

Definition at line 295 of file evaluator.py.

◆ _planning_execution_time_subscription_

evaluator.evaluator.Evaluator._planning_execution_time_subscription_
protected

Definition at line 153 of file evaluator.py.

◆ _planning_mean_difference_to_cones

evaluator.evaluator.Evaluator._planning_mean_difference_to_cones
protected

Definition at line 264 of file evaluator.py.

◆ _planning_mean_difference_to_gt

evaluator.evaluator.Evaluator._planning_mean_difference_to_gt
protected

Definition at line 234 of file evaluator.py.

◆ _planning_mean_difference_to_left_cones

evaluator.evaluator.Evaluator._planning_mean_difference_to_left_cones
protected

Definition at line 244 of file evaluator.py.

◆ _planning_mean_difference_to_right_cones

evaluator.evaluator.Evaluator._planning_mean_difference_to_right_cones
protected

Definition at line 254 of file evaluator.py.

◆ _planning_mean_mean_error

evaluator.evaluator.Evaluator._planning_mean_mean_error
protected

Definition at line 416 of file evaluator.py.

◆ _planning_mean_mean_root_squared_error

evaluator.evaluator.Evaluator._planning_mean_mean_root_squared_error
protected

Definition at line 424 of file evaluator.py.

◆ _planning_mean_mean_squared_error

evaluator.evaluator.Evaluator._planning_mean_mean_squared_error
protected

Definition at line 420 of file evaluator.py.

◆ _planning_mean_root_squared_sum_error

evaluator.evaluator.Evaluator._planning_mean_root_squared_sum_error
protected

Definition at line 336 of file evaluator.py.

◆ _planning_mean_squared_difference_to_cones

evaluator.evaluator.Evaluator._planning_mean_squared_difference_to_cones
protected

Definition at line 267 of file evaluator.py.

◆ _planning_mean_squared_difference_to_gt

evaluator.evaluator.Evaluator._planning_mean_squared_difference_to_gt
protected

Definition at line 237 of file evaluator.py.

◆ _planning_mean_squared_difference_to_left_cones

evaluator.evaluator.Evaluator._planning_mean_squared_difference_to_left_cones
protected

Definition at line 247 of file evaluator.py.

◆ _planning_mean_squared_difference_to_right_cones

evaluator.evaluator.Evaluator._planning_mean_squared_difference_to_right_cones
protected

Definition at line 257 of file evaluator.py.

◆ _planning_root_mean_squared_difference_to_cones

evaluator.evaluator.Evaluator._planning_root_mean_squared_difference_to_cones
protected

Definition at line 270 of file evaluator.py.

◆ _planning_root_mean_squared_difference_to_gt

evaluator.evaluator.Evaluator._planning_root_mean_squared_difference_to_gt
protected

Definition at line 240 of file evaluator.py.

◆ _planning_root_mean_squared_difference_to_left_cones

evaluator.evaluator.Evaluator._planning_root_mean_squared_difference_to_left_cones
protected

Definition at line 250 of file evaluator.py.

◆ _planning_root_mean_squared_difference_to_right_cones

evaluator.evaluator.Evaluator._planning_root_mean_squared_difference_to_right_cones
protected

Definition at line 260 of file evaluator.py.

◆ _planning_squared_sum_error

evaluator.evaluator.Evaluator._planning_squared_sum_error
protected

Definition at line 335 of file evaluator.py.

◆ _planning_sum_error

evaluator.evaluator.Evaluator._planning_sum_error
protected

Definition at line 334 of file evaluator.py.

◆ _pose_count_

evaluator.evaluator.Evaluator._pose_count_
protected

Definition at line 315 of file evaluator.py.

◆ _prediction_step_time_subscription_

evaluator.evaluator.Evaluator._prediction_step_time_subscription_
protected

Definition at line 147 of file evaluator.py.

◆ _se_correction_execution_time_

evaluator.evaluator.Evaluator._se_correction_execution_time_
protected

Definition at line 292 of file evaluator.py.

◆ _se_difference_with_map_

evaluator.evaluator.Evaluator._se_difference_with_map_
protected

Definition at line 229 of file evaluator.py.

◆ _se_false_positives_

evaluator.evaluator.Evaluator._se_false_positives_
protected

Definition at line 223 of file evaluator.py.

◆ _se_map_mean_root_squared_sum_error

evaluator.evaluator.Evaluator._se_map_mean_root_squared_sum_error
protected

Definition at line 313 of file evaluator.py.

◆ _se_map_squared_sum_error

evaluator.evaluator.Evaluator._se_map_squared_sum_error
protected

Definition at line 312 of file evaluator.py.

◆ _se_map_sum_error

evaluator.evaluator.Evaluator._se_map_sum_error
protected

Definition at line 311 of file evaluator.py.

◆ _se_number_duplicates

evaluator.evaluator.Evaluator._se_number_duplicates
protected

Definition at line 226 of file evaluator.py.

◆ _se_prediction_execution_time_

evaluator.evaluator.Evaluator._se_prediction_execution_time_
protected

Definition at line 293 of file evaluator.py.

◆ _state_estimation_mean_squared_vehicle_pose_error

evaluator.evaluator.Evaluator._state_estimation_mean_squared_vehicle_pose_error
protected

Definition at line 381 of file evaluator.py.

◆ _state_estimation_mean_squared_velocities_error

evaluator.evaluator.Evaluator._state_estimation_mean_squared_velocities_error
protected

Definition at line 401 of file evaluator.py.

◆ _state_estimation_mean_vehicle_pose_error

evaluator.evaluator.Evaluator._state_estimation_mean_vehicle_pose_error
protected

Definition at line 375 of file evaluator.py.

◆ _state_estimation_mean_velocities_error

evaluator.evaluator.Evaluator._state_estimation_mean_velocities_error
protected

Definition at line 395 of file evaluator.py.

◆ _state_estimation_root_mean_squared_vehicle_pose_error

evaluator.evaluator.Evaluator._state_estimation_root_mean_squared_vehicle_pose_error
protected

Definition at line 387 of file evaluator.py.

◆ _state_estimation_root_mean_squared_velocities_error

evaluator.evaluator.Evaluator._state_estimation_root_mean_squared_velocities_error
protected

Definition at line 407 of file evaluator.py.

◆ _sum_squared_vehicle_pose_error

evaluator.evaluator.Evaluator._sum_squared_vehicle_pose_error
protected

Definition at line 327 of file evaluator.py.

◆ _sum_squared_velocities_error

evaluator.evaluator.Evaluator._sum_squared_velocities_error
protected

Definition at line 319 of file evaluator.py.

◆ _sum_vehicle_pose_error

evaluator.evaluator.Evaluator._sum_vehicle_pose_error
protected

Definition at line 326 of file evaluator.py.

◆ _sum_velocities_error

evaluator.evaluator.Evaluator._sum_velocities_error
protected

Definition at line 318 of file evaluator.py.

◆ _transforms_listener_

evaluator.evaluator.Evaluator._transforms_listener_
protected

Definition at line 128 of file evaluator.py.

◆ _ve_count_

evaluator.evaluator.Evaluator._ve_count_
protected

Definition at line 316 of file evaluator.py.

◆ _vehicle_pose_difference_

evaluator.evaluator.Evaluator._vehicle_pose_difference_
protected

Definition at line 208 of file evaluator.py.

◆ _velocities_difference_

evaluator.evaluator.Evaluator._velocities_difference_
protected

Definition at line 203 of file evaluator.py.

◆ absolute_velocity

evaluator.evaluator.Evaluator.absolute_velocity

Definition at line 174 of file evaluator.py.

◆ compute_and_publish_control

evaluator.evaluator.Evaluator.compute_and_publish_control

Definition at line 168 of file evaluator.py.

◆ control_metrics

evaluator.evaluator.Evaluator.control_metrics

Definition at line 291 of file evaluator.py.

◆ correction_step_time_callback

evaluator.evaluator.Evaluator.correction_step_time_callback

Definition at line 144 of file evaluator.py.

◆ csv_suffix

evaluator.evaluator.Evaluator.csv_suffix

Definition at line 283 of file evaluator.py.

◆ generate_csv

evaluator.evaluator.Evaluator.generate_csv

Definition at line 494 of file evaluator.py.

◆ map_metrics

evaluator.evaluator.Evaluator.map_metrics

Definition at line 287 of file evaluator.py.

◆ map_subscription_

evaluator.evaluator.Evaluator.map_subscription_

Definition at line 87 of file evaluator.py.

◆ path_points

evaluator.evaluator.Evaluator.path_points

Definition at line 172 of file evaluator.py.

◆ perception_execution_time_callback

evaluator.evaluator.Evaluator.perception_execution_time_callback

Definition at line 162 of file evaluator.py.

◆ perception_metrics

evaluator.evaluator.Evaluator.perception_metrics

Definition at line 286 of file evaluator.py.

◆ perception_subscription_

evaluator.evaluator.Evaluator.perception_subscription_

Definition at line 84 of file evaluator.py.

◆ planning_execution_time_callback

evaluator.evaluator.Evaluator.planning_execution_time_callback

Definition at line 156 of file evaluator.py.

◆ planning_gt_subscription_

evaluator.evaluator.Evaluator.planning_gt_subscription_

Definition at line 129 of file evaluator.py.

◆ planning_metrics

evaluator.evaluator.Evaluator.planning_metrics

Definition at line 290 of file evaluator.py.

◆ planning_subscription_

evaluator.evaluator.Evaluator.planning_subscription_

Definition at line 96 of file evaluator.py.

◆ pose_metrics

evaluator.evaluator.Evaluator.pose_metrics

Definition at line 288 of file evaluator.py.

◆ position

evaluator.evaluator.Evaluator.position

Definition at line 173 of file evaluator.py.

◆ prediction_step_time_callback

evaluator.evaluator.Evaluator.prediction_step_time_callback

Definition at line 150 of file evaluator.py.

◆ signal_handler

evaluator.evaluator.Evaluator.signal_handler

Definition at line 458 of file evaluator.py.

◆ transform_buffer_

evaluator.evaluator.Evaluator.transform_buffer_

Definition at line 127 of file evaluator.py.

◆ use_simulated_perception_

evaluator.evaluator.Evaluator.use_simulated_perception_

Definition at line 478 of file evaluator.py.

◆ use_simulated_planning_

evaluator.evaluator.Evaluator.use_simulated_planning_

Definition at line 485 of file evaluator.py.

◆ use_simulated_se_

evaluator.evaluator.Evaluator.use_simulated_se_

Definition at line 481 of file evaluator.py.

◆ use_simulated_velocities_

evaluator.evaluator.Evaluator.use_simulated_velocities_

Definition at line 482 of file evaluator.py.

◆ vehicle_pose_subscription_

evaluator.evaluator.Evaluator.vehicle_pose_subscription_

Definition at line 93 of file evaluator.py.

◆ vel_estimation_metrics

evaluator.evaluator.Evaluator.vel_estimation_metrics

Definition at line 289 of file evaluator.py.

◆ velocities_subscription_

evaluator.evaluator.Evaluator.velocities_subscription_

Definition at line 90 of file evaluator.py.


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