Skip to content

Commit

Permalink
docs: fix spelling mistakes (#296) (#297)
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu authored Feb 14, 2024
1 parent 68dc12f commit 1d7d506
Show file tree
Hide file tree
Showing 4 changed files with 18 additions and 18 deletions.
4 changes: 2 additions & 2 deletions ouster-ros/include/ouster_ros/os_point.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
8 changes: 4 additions & 4 deletions ouster-ros/src/os_sensor_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,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;
}

Expand All @@ -157,7 +157,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;
}

Expand Down Expand Up @@ -409,7 +409,7 @@ std::shared_ptr<sensor::client> OusterSensor::create_sensor_client(

std::shared_ptr<sensor::client> 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) {
Expand Down Expand Up @@ -711,7 +711,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();
Expand Down
6 changes: 3 additions & 3 deletions ouster-ros/src/point_cloud_compose.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ struct TypeSelector<ChanFieldType::UINT64> {
/**
* @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 <std::size_t Index, std::size_t N, const ChanFieldTable<N>& Table>
constexpr auto make_lidar_scan_tuple() {
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -141,7 +141,7 @@ void scan_to_cloud_f_destaggered(ouster_ros::Cloud<PointT>& cloud,
pt.y = static_cast<decltype(pt.y)>(xyz(1));
pt.z = static_cast<decltype(pt.z)>(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<uint32_t>(ts);
Expand Down
18 changes: 9 additions & 9 deletions ouster-ros/src/point_cloud_processor_factory.h
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ class PointCloudProcessorFactory {
}

template <typename PointT>
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) {
Expand All @@ -107,41 +107,41 @@ class PointCloudProcessorFactory {
if (point_type == "native") {
switch (info.format.udp_profile_lidar) {
case UDPProfileLidar::PROFILE_LIDAR_LEGACY:
return make_point_cloud_procssor<Point_LEGACY>(
return make_point_cloud_processor<Point_LEGACY>(
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<Point_RNG15_RFL8_NIR8>(
return make_point_cloud_processor<Point_RNG15_RFL8_NIR8>(
info, frame, apply_lidar_to_sensor_transform,
post_processing_fn);
default:
// TODO: implement fallback?
throw std::runtime_error("unsupported udp_profile_lidar");
}
} else if (point_type == "xyz") {
return make_point_cloud_procssor<pcl::PointXYZ>(
return make_point_cloud_processor<pcl::PointXYZ>(
info, frame, apply_lidar_to_sensor_transform,
post_processing_fn);
} else if (point_type == "xyzi") {
return make_point_cloud_procssor<pcl::PointXYZI>(
return make_point_cloud_processor<pcl::PointXYZI>(
info, frame, apply_lidar_to_sensor_transform,
post_processing_fn);
} else if (point_type == "xyzir") {
return make_point_cloud_procssor<PointXYZIR>(
return make_point_cloud_processor<PointXYZIR>(
info, frame, apply_lidar_to_sensor_transform,
post_processing_fn);
} else if (point_type == "original") {
return make_point_cloud_procssor<ouster_ros::Point>(
return make_point_cloud_processor<ouster_ros::Point>(
info, frame, apply_lidar_to_sensor_transform,
post_processing_fn);
}
Expand Down

0 comments on commit 1d7d506

Please sign in to comment.