Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Changed intensity from float to uint8 #118

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion doc/howto/05_how_to_change_point_type.md
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ rslidar_sdk transforms point cloud of `PointXYZIRT` to ROS message of `PointClou
addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::UINT8, offset);
#ifdef POINT_TYPE_XYZIRT
sensor_msgs::PointCloud2Iterator<uint16_t> iter_ring_(ros_msg, "ring");
sensor_msgs::PointCloud2Iterator<double> iter_timestamp_(ros_msg, "timestamp");
Expand Down
2 changes: 1 addition & 1 deletion doc/howto/05_how_to_change_point_type_CN.md
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ rslidar_sdk将基于`PointXYZIRT`的点云,转换为ROS的PointCloud2消息,
addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::UINT8, offset);
#ifdef POINT_TYPE_XYZIRT
sensor_msgs::PointCloud2Iterator<uint16_t> iter_ring_(ros_msg, "ring");
sensor_msgs::PointCloud2Iterator<double> iter_timestamp_(ros_msg, "timestamp");
Expand Down
8 changes: 4 additions & 4 deletions src/source/source_pointcloud_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ inline sensor_msgs::PointCloud2 toRosMsg(const LidarPointCloudMsg& rs_msg, const
offset = addPointField(ros_msg, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
offset = addPointField(ros_msg, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
offset = addPointField(ros_msg, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::FLOAT32, offset);
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::PointField::UINT8, offset);
#ifdef POINT_TYPE_XYZIRT
offset = addPointField(ros_msg, "ring", 1, sensor_msgs::PointField::UINT16, offset);
offset = addPointField(ros_msg, "timestamp", 1, sensor_msgs::PointField::FLOAT64, offset);
Expand All @@ -87,7 +87,7 @@ inline sensor_msgs::PointCloud2 toRosMsg(const LidarPointCloudMsg& rs_msg, const
sensor_msgs::PointCloud2Iterator<float> iter_x_(ros_msg, "x");
sensor_msgs::PointCloud2Iterator<float> iter_y_(ros_msg, "y");
sensor_msgs::PointCloud2Iterator<float> iter_z_(ros_msg, "z");
sensor_msgs::PointCloud2Iterator<float> iter_intensity_(ros_msg, "intensity");
sensor_msgs::PointCloud2Iterator<uint8_t> iter_intensity_(ros_msg, "intensity");
#ifdef POINT_TYPE_XYZIRT
sensor_msgs::PointCloud2Iterator<uint16_t> iter_ring_(ros_msg, "ring");
sensor_msgs::PointCloud2Iterator<double> iter_timestamp_(ros_msg, "timestamp");
Expand Down Expand Up @@ -236,7 +236,7 @@ inline sensor_msgs::msg::PointCloud2 toRosMsg(const LidarPointCloudMsg& rs_msg,
offset = addPointField(ros_msg, "x", 1, sensor_msgs::msg::PointField::FLOAT32, offset);
offset = addPointField(ros_msg, "y", 1, sensor_msgs::msg::PointField::FLOAT32, offset);
offset = addPointField(ros_msg, "z", 1, sensor_msgs::msg::PointField::FLOAT32, offset);
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::msg::PointField::FLOAT32, offset);
offset = addPointField(ros_msg, "intensity", 1, sensor_msgs::msg::PointField::UINT8, offset);
#ifdef POINT_TYPE_XYZIRT
offset = addPointField(ros_msg, "ring", 1, sensor_msgs::msg::PointField::UINT16, offset);
offset = addPointField(ros_msg, "timestamp", 1, sensor_msgs::msg::PointField::FLOAT64, offset);
Expand All @@ -254,7 +254,7 @@ inline sensor_msgs::msg::PointCloud2 toRosMsg(const LidarPointCloudMsg& rs_msg,
sensor_msgs::PointCloud2Iterator<float> iter_x_(ros_msg, "x");
sensor_msgs::PointCloud2Iterator<float> iter_y_(ros_msg, "y");
sensor_msgs::PointCloud2Iterator<float> iter_z_(ros_msg, "z");
sensor_msgs::PointCloud2Iterator<float> iter_intensity_(ros_msg, "intensity");
sensor_msgs::PointCloud2Iterator<uint8_t> iter_intensity_(ros_msg, "intensity");
#ifdef POINT_TYPE_XYZIRT
sensor_msgs::PointCloud2Iterator<uint16_t> iter_ring_(ros_msg, "ring");
sensor_msgs::PointCloud2Iterator<double> iter_timestamp_(ros_msg, "timestamp");
Expand Down