Skip to content

Commit

Permalink
Formatting + documentation
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu committed Oct 31, 2023
1 parent 25d9be1 commit 7697611
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 20 deletions.
34 changes: 17 additions & 17 deletions ouster-ros/config/driver_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -67,21 +67,21 @@ ouster/os_driver:
# data QoS. This is preferrable for production but default QoS is needed for
# rosbag. See: https://github.com/ros2/rosbag2/issues/125
use_system_default_qos: false
# point_type[optional]: choose from: {original, native, xyz, xyzi, xyzir}
# Here is a breif description of each option:
# - original: ouster_ros::Point
# - native: directly maps all fields as published by the sensor to an
# equivalent point cloud representation with the additon of ring
# and timestamp fields.
# - xyz: the simplest point type, only has {x, y, z}
# - xyzi: same as xyz point type but adds intensity (signal) field. this
# type is not compatible with the low data profile.
# - xyzir: same as xyzi type but adds ring (channel) field.
# this type is same as Velodyne point cloud type
# this type is not compatible with the low data profile.
# for more details about the fields of each point type and their data refer
# to the following header files:
# - ouster_ros/os_point.h
# - ouster_ros/sensor_point_types.h
# - ouster_ros/common_point_types.h.
# point_type[optional]: choose from: {original, native, xyz, xyzi, xyzir}
# Here is a breif description of each option:
# - original: ouster_ros::Point
# - native: directly maps all fields as published by the sensor to an
# equivalent point cloud representation with the additon of ring
# and timestamp fields.
# - xyz: the simplest point type, only has {x, y, z}
# - xyzi: same as xyz point type but adds intensity (signal) field. this
# type is not compatible with the low data profile.
# - xyzir: same as xyzi type but adds ring (channel) field.
# this type is same as Velodyne point cloud type
# this type is not compatible with the low data profile.
# for more details about the fields of each point type and their data refer
# to the following header files:
# - ouster_ros/os_point.h
# - ouster_ros/sensor_point_types.h
# - ouster_ros/common_point_types.h.
point_type: original
2 changes: 1 addition & 1 deletion ouster-ros/include/ouster_ros/os_point.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ namespace ouster_ros {
// active udp lidar profile.
struct EIGEN_ALIGN16 _Point {
PCL_ADD_POINT4D;
float intensity; // equivalent signal
float intensity; // equivalent to signal
uint32_t t;
uint16_t reflectivity;
uint16_t ring; // equivalent to channel
Expand Down
4 changes: 2 additions & 2 deletions ouster-ros/src/point_cloud_compose.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,8 @@ constexpr auto make_lidar_scan_tuple(const ouster::LidarScan& ls) {
/**
* @brief copies field values from LidarScan fields combined as a tuple into the
* the corresponding elements of the input point pt.
* @param[in,out] pt
* @param[in] tp
* @param[out] pt point to copy values into.
* @param[in] tp tuple containing arrays to copy LidarScan field values from.
* @param[in] idx index of the point to be copied.
* @remark this method is to be used mainly with sensor native point types.
*/
Expand Down

0 comments on commit 7697611

Please sign in to comment.