From 3f9790713efb56099a7348aec6bdefa3e6807279 Mon Sep 17 00:00:00 2001 From: Andre Nguyen Date: Wed, 14 Feb 2024 13:03:40 -0500 Subject: [PATCH] docs: fix spelling mistakes (#296) --- ouster-ros/include/ouster_ros/os_point.h | 4 ++-- ouster-ros/src/os_sensor_node.cpp | 8 ++++---- ouster-ros/src/point_cloud_compose.h | 6 +++--- ouster-ros/src/point_cloud_processor_factory.h | 18 +++++++++--------- 4 files changed, 18 insertions(+), 18 deletions(-) diff --git a/ouster-ros/include/ouster_ros/os_point.h b/ouster-ros/include/ouster_ros/os_point.h index e319220d..0a174f3f 100644 --- a/ouster-ros/include/ouster_ros/os_point.h +++ b/ouster-ros/include/ouster_ros/os_point.h @@ -12,9 +12,9 @@ namespace ouster_ros { -// The default/original represntation of the point cloud since the driver +// The default/original representation of the point cloud since the driver // inception. This shouldn't be confused with Point_LEGACY which provides exact -// mapping of the fields of Ouster LidarScan of the Legacy Profile, copying the +// mapping of the fields of Ouster LidarScan of the Legacy Profile, copying // the same order and using the same bit representation. For example, this Point // struct uses float data type to represent intensity (aka signal); however, the // sensor sends the signal channel either as UINT16 or UINT32 depending on the diff --git a/ouster-ros/src/os_sensor_node.cpp b/ouster-ros/src/os_sensor_node.cpp index ca52a39c..d8fedb37 100644 --- a/ouster-ros/src/os_sensor_node.cpp +++ b/ouster-ros/src/os_sensor_node.cpp @@ -128,7 +128,7 @@ LifecycleNodeInterface::CallbackReturn OusterSensor::on_cleanup( } catch (const std::exception& ex) { RCLCPP_ERROR_STREAM( get_logger(), - "exception thrown durng cleanup, details: " << ex.what()); + "exception thrown during cleanup, details: " << ex.what()); return LifecycleNodeInterface::CallbackReturn::ERROR; } @@ -155,7 +155,7 @@ LifecycleNodeInterface::CallbackReturn OusterSensor::on_shutdown( } catch (const std::exception& ex) { RCLCPP_ERROR_STREAM( get_logger(), - "exception thrown durng cleanup, details: " << ex.what()); + "exception thrown during cleanup, details: " << ex.what()); return LifecycleNodeInterface::CallbackReturn::ERROR; } @@ -407,7 +407,7 @@ std::shared_ptr OusterSensor::create_sensor_client( std::shared_ptr cli; if (sensor::in_multicast(udp_dest)) { - // use the mtp_init_client to recieve data via multicast + // use the mtp_init_client to receive data via multicast // if mtp_main is true when sensor will be configured cli = sensor::mtp_init_client(hostname, config, mtp_dest, mtp_main); } else if (lidar_port != 0 && imu_port != 0) { @@ -709,7 +709,7 @@ void OusterSensor::handle_lidar_packet(sensor::client& cli, if (success) { read_lidar_packet_errors = 0; if (!is_legacy_lidar_profile(info) && init_id_changed(pf, buffer)) { - // TODO: short circut reset if no breaking changes occured? + // TODO: short circuit reset if no breaking changes occured? RCLCPP_WARN(get_logger(), "sensor init_id has changed! reactivating.."); reactivate_sensor(); diff --git a/ouster-ros/src/point_cloud_compose.h b/ouster-ros/src/point_cloud_compose.h index 9183cf11..8aa2a79f 100644 --- a/ouster-ros/src/point_cloud_compose.h +++ b/ouster-ros/src/point_cloud_compose.h @@ -41,7 +41,7 @@ struct TypeSelector { /** * @brief constructs a suitable tuple at compile time that can store a reference * to all the fields of a specific LidarScan object (without conversion) - * according to the information specificed by the ChanFieldTable. + * according to the information specified by the ChanFieldTable. */ template & Table> constexpr auto make_lidar_scan_tuple() { @@ -79,7 +79,7 @@ void map_lidar_scan_fields_to_tuple(Tuple& tp, const ouster::LidarScan& ls) { /** * @brief constructs a suitable tuple at compile time that can store a reference * to all the fields of a specific LidarScan object (without conversion) - * according to the information specificed by the ChanFieldTable and directly + * according to the information specified by the ChanFieldTable and directly * maps the fields of the supplied LidarScan to the constructed tuple before * returning. * @param[in] ls LidarScan @@ -141,7 +141,7 @@ void scan_to_cloud_f_destaggered(ouster_ros::Cloud& cloud, pt.y = static_cast(xyz(1)); pt.z = static_cast(xyz(2)); // TODO: in the future we could probably skip copying t and ring - // values if knowning before hand that the target point cloud does + // values if knowing before hand that the target point cloud does // not have a field to hold the timestamp or a ring for example the // case of pcl::PointXYZ or pcl::PointXYZI. pt.t = static_cast(ts); diff --git a/ouster-ros/src/point_cloud_processor_factory.h b/ouster-ros/src/point_cloud_processor_factory.h index 859e92da..fcbb075d 100644 --- a/ouster-ros/src/point_cloud_processor_factory.h +++ b/ouster-ros/src/point_cloud_processor_factory.h @@ -84,7 +84,7 @@ class PointCloudProcessorFactory { } template - static LidarScanProcessor make_point_cloud_procssor( + static LidarScanProcessor make_point_cloud_processor( const sensor::sensor_info& info, const std::string& frame, bool apply_lidar_to_sensor_transform, PointCloudProcessor_PostProcessingFn post_processing_fn) { @@ -107,21 +107,21 @@ class PointCloudProcessorFactory { if (point_type == "native") { switch (info.format.udp_profile_lidar) { case UDPProfileLidar::PROFILE_LIDAR_LEGACY: - return make_point_cloud_procssor( + return make_point_cloud_processor( info, frame, apply_lidar_to_sensor_transform, post_processing_fn); case UDPProfileLidar::PROFILE_RNG19_RFL8_SIG16_NIR16_DUAL: - return make_point_cloud_procssor< + return make_point_cloud_processor< Point_RNG19_RFL8_SIG16_NIR16_DUAL>( info, frame, apply_lidar_to_sensor_transform, post_processing_fn); case UDPProfileLidar::PROFILE_RNG19_RFL8_SIG16_NIR16: - return make_point_cloud_procssor< + return make_point_cloud_processor< Point_RNG19_RFL8_SIG16_NIR16>( info, frame, apply_lidar_to_sensor_transform, post_processing_fn); case UDPProfileLidar::PROFILE_RNG15_RFL8_NIR8: - return make_point_cloud_procssor( + return make_point_cloud_processor( info, frame, apply_lidar_to_sensor_transform, post_processing_fn); default: @@ -129,19 +129,19 @@ class PointCloudProcessorFactory { throw std::runtime_error("unsupported udp_profile_lidar"); } } else if (point_type == "xyz") { - return make_point_cloud_procssor( + return make_point_cloud_processor( info, frame, apply_lidar_to_sensor_transform, post_processing_fn); } else if (point_type == "xyzi") { - return make_point_cloud_procssor( + return make_point_cloud_processor( info, frame, apply_lidar_to_sensor_transform, post_processing_fn); } else if (point_type == "xyzir") { - return make_point_cloud_procssor( + return make_point_cloud_processor( info, frame, apply_lidar_to_sensor_transform, post_processing_fn); } else if (point_type == "original") { - return make_point_cloud_procssor( + return make_point_cloud_processor( info, frame, apply_lidar_to_sensor_transform, post_processing_fn); }