Skip to content
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 AirLib/include/sensors/lidar/LidarBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ namespace airlib
UpdatableObject::reportState(reporter);

reporter.writeValue("Lidar-Timestamp", output_.time_stamp);
reporter.writeValue("Lidar-NumPoints", static_cast<int>(output_.point_cloud.size() / 3));
reporter.writeValue("Lidar-NumPoints", static_cast<int>(output_.point_cloud.size() / 4));
}

const LidarData& getOutput() const
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,7 @@ void UnrealLidarSensor::getPointCloud(const msr::airlib::Pose& lidar_pose, const
point_cloud.emplace_back(point.x());
point_cloud.emplace_back(point.y());
point_cloud.emplace_back(point.z());
point_cloud.emplace_back(laser);
segmentation_cloud.emplace_back(segmentationID);
}
}
Expand Down
7 changes: 4 additions & 3 deletions ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -733,14 +733,15 @@ sensor_msgs::PointCloud2 AirsimROSWrapper::get_lidar_msg_from_airsim(const msr::
lidar_msg.header.stamp = ros::Time::now();
lidar_msg.header.frame_id = vehicle_name + "/" + sensor_name;

if (lidar_data.point_cloud.size() > 3) {
if (lidar_data.point_cloud.size() > 4) {
lidar_msg.height = 1;
lidar_msg.width = lidar_data.point_cloud.size() / 3;
lidar_msg.width = lidar_data.point_cloud.size() / 4;

lidar_msg.fields.resize(3);
lidar_msg.fields.resize(4);
lidar_msg.fields[0].name = "x";
lidar_msg.fields[1].name = "y";
lidar_msg.fields[2].name = "z";
lidar_msg.fields[3].name = "ring";

int offset = 0;

Expand Down
7 changes: 4 additions & 3 deletions ros2/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -651,14 +651,15 @@ sensor_msgs::msg::PointCloud2 AirsimROSWrapper::get_lidar_msg_from_airsim(const
lidar_msg.header.stamp = rclcpp::Time(lidar_data.time_stamp);
lidar_msg.header.frame_id = vehicle_name + "/" + sensor_name;

if (lidar_data.point_cloud.size() > 3) {
if (lidar_data.point_cloud.size() > 4) {
lidar_msg.height = 1;
lidar_msg.width = lidar_data.point_cloud.size() / 3;
lidar_msg.width = lidar_data.point_cloud.size() / 4;

lidar_msg.fields.resize(3);
lidar_msg.fields.resize(4);
lidar_msg.fields[0].name = "x";
lidar_msg.fields[1].name = "y";
lidar_msg.fields[2].name = "z";
lidar_msg.fields[3].name = "ring";

int offset = 0;

Expand Down