diff --git a/calibrators/marker_radar_lidar_calibrator/include/marker_radar_lidar_calibrator/visualization.hpp b/calibrators/marker_radar_lidar_calibrator/include/marker_radar_lidar_calibrator/visualization.hpp index 4bd22101..d9a222bf 100644 --- a/calibrators/marker_radar_lidar_calibrator/include/marker_radar_lidar_calibrator/visualization.hpp +++ b/calibrators/marker_radar_lidar_calibrator/include/marker_radar_lidar_calibrator/visualization.hpp @@ -26,7 +26,7 @@ namespace marker_radar_lidar_calibrator { -struct VisualizationParamters +struct VisualizationParameters { std_msgs::msg::Header lidar_header; std_msgs::msg::Header radar_header; @@ -49,7 +49,7 @@ class Visualization Visualization() = default; ~Visualization() = default; - void setParameters(VisualizationParamters params); + void setParameters(VisualizationParameters params); DetectionMarkers visualizeDetectionMarkers( const std::vector & lidar_detections, const std::vector & radar_detections, @@ -63,7 +63,7 @@ class Visualization const size_t converged_tracks_size, TransformationType type, CalibrationErrorMetrics metrics); private: - VisualizationParamters params_; + VisualizationParameters params_; static constexpr double m_to_cm = 100.0; }; diff --git a/calibrators/marker_radar_lidar_calibrator/scripts/metrics_plotter_node.py b/calibrators/marker_radar_lidar_calibrator/scripts/metrics_plotter_node.py index e0796ce9..48e276cc 100755 --- a/calibrators/marker_radar_lidar_calibrator/scripts/metrics_plotter_node.py +++ b/calibrators/marker_radar_lidar_calibrator/scripts/metrics_plotter_node.py @@ -17,7 +17,7 @@ import math import matplotlib.pyplot as plt -import matplotlib.ticker as mticker +import matplotlib.ticker as mticker # cspell:ignore mticker import numpy as np import rclpy from rclpy.node import Node diff --git a/calibrators/marker_radar_lidar_calibrator/src/marker_radar_lidar_calibrator.cpp b/calibrators/marker_radar_lidar_calibrator/src/marker_radar_lidar_calibrator.cpp index 30438b04..ab5b8a11 100644 --- a/calibrators/marker_radar_lidar_calibrator/src/marker_radar_lidar_calibrator.cpp +++ b/calibrators/marker_radar_lidar_calibrator/src/marker_radar_lidar_calibrator.cpp @@ -1287,7 +1287,7 @@ bool ExtrinsicReflectorBasedCalibrator::checkInitialTransforms() } // Set visualization parameters - VisualizationParamters params; + VisualizationParameters params; params.lidar_header = lidar_header_; params.radar_header = radar_header_; params.transformation_type = transformation_type_; @@ -1615,7 +1615,7 @@ TransformationResult ExtrinsicReflectorBasedCalibrator::estimateTransformation() << initial_radar_to_lidar_eigen_.matrix()); RCLCPP_INFO_STREAM( this->get_logger(), - "Yaw-only roatation 2D radar->lidar transform:\n" + "Yaw-only rotation 2D radar->lidar transform:\n" << transformation_result .calibrated_radar_to_lidar_transformations[TransformationType::yaw_only_rotation_2d] .matrix()); diff --git a/calibrators/marker_radar_lidar_calibrator/src/visualization.cpp b/calibrators/marker_radar_lidar_calibrator/src/visualization.cpp index 8f360543..8db17229 100644 --- a/calibrators/marker_radar_lidar_calibrator/src/visualization.cpp +++ b/calibrators/marker_radar_lidar_calibrator/src/visualization.cpp @@ -22,7 +22,7 @@ namespace marker_radar_lidar_calibrator { -void Visualization::setParameters(VisualizationParamters params) { params_ = params; } +void Visualization::setParameters(VisualizationParameters params) { params_ = params; } DetectionMarkers Visualization::visualizeDetectionMarkers( const std::vector & lidar_detections,