Skip to content

Commit

Permalink
chore: fix spell errors
Browse files Browse the repository at this point in the history
Signed-off-by: vividf <[email protected]>
  • Loading branch information
vividf committed Dec 17, 2024
1 parent bed955d commit f734537
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -49,7 +49,7 @@ class Visualization
Visualization() = default;
~Visualization() = default;

void setParameters(VisualizationParamters params);
void setParameters(VisualizationParameters params);
DetectionMarkers visualizeDetectionMarkers(
const std::vector<Eigen::Vector3d> & lidar_detections,
const std::vector<Eigen::Vector3d> & radar_detections,
Expand All @@ -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;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
Expand Down Expand Up @@ -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());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Eigen::Vector3d> & lidar_detections,
Expand Down

0 comments on commit f734537

Please sign in to comment.