Skip to content

Commit

Permalink
Port destaggered point cloud changes to foxy (#187)
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu authored Aug 10, 2023
1 parent 60fce53 commit 5fd074e
Show file tree
Hide file tree
Showing 13 changed files with 392 additions and 18 deletions.
5 changes: 5 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,11 @@ Changelog

[unreleased]
============
* breaking: publish PCL point clouds destaggered.


ouster_ros v0.10.0
==================

ouster_ros(2)
-------------
Expand Down
262 changes: 262 additions & 0 deletions ouster-ros/config/viz-reliable.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,262 @@
Panels:
- Class: rviz_common/Displays
Help Height: 138
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /PointCloud21
- /TF1/Tree1
- /range1
- /range1/Topic1
- /nearir1/Topic1
- /reflec1
- /signal1
Splitter Ratio: 0.5
Tree Height: 1185
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Goal Pose1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz_common/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: PointCloud2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Autocompute Intensity Bounds: false
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: range
Class: rviz_default_plugins/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Invert Rainbow: true
Max Color: 255; 255; 255
Max Intensity: 10000
Min Color: 0; 0; 0
Min Intensity: 0
Name: PointCloud2
Position Transformer: XYZ
Selectable: true
Size (Pixels): 3
Size (m): 0.009999999776482582
Style: Flat Squares
Topic:
Depth: 5
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /ouster/points
Use Fixed Frame: true
Use rainbow: true
Value: true
- Class: rviz_default_plugins/TF
Enabled: true
Frame Timeout: 15
Frames:
" os_imu":
Value: true
" os_lidar":
Value: true
" os_sensor":
Value: true
All Enabled: true
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: false
Tree:
" os_sensor":
" os_imu":
{}
" os_lidar":
{}
Update Interval: 0
Value: true
- Class: rviz_default_plugins/Image
Enabled: true
Max Value: 1
Median window: 5
Min Value: 0
Name: range
Normalize Range: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /ouster/range_image
Value: true
- Class: rviz_default_plugins/Image
Enabled: true
Max Value: 1
Median window: 5
Min Value: 0
Name: nearir
Normalize Range: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /ouster/nearir_image
Value: true
- Class: rviz_default_plugins/Image
Enabled: true
Max Value: 1
Median window: 5
Min Value: 0
Name: reflec
Normalize Range: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /ouster/reflec_image
Value: true
- Class: rviz_default_plugins/Image
Enabled: true
Max Value: 1
Median window: 5
Min Value: 0
Name: signal
Normalize Range: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /ouster/signal_image
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: "os_sensor"
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Covariance x: 0.25
Covariance y: 0.25
Covariance yaw: 0.06853891909122467
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 4.583338260650635
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.9003978371620178
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 4.277213096618652
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 2272
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd0000000400000000000001f700000599fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000002b3000005990000018200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000015f000007defc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000006e000007de0000013200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000e7000000239fc0100000002fc0000000000000e700000008d00fffffffa000000010200000004fb0000000c007200650066006c006500630000000000ffffffff0000004a00fffffffb0000000c007300690067006e0061006c0100000000ffffffff0000004a00fffffffb0000000c006e006500610072006900720000000000ffffffff0000004a00fffffffb0000000a00720061006e00670065000000006e000002390000004a00fffffffb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000e700000005afc0100000002fb0000000800540069006d0065010000000000000e700000057100fffffffb0000000800540069006d0065010000000000000450000000000000000000000c6d0000059900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 3696
X: 144
Y: 54
nearir:
collapsed: false
range:
collapsed: false
reflec:
collapsed: false
signal:
collapsed: false
21 changes: 21 additions & 0 deletions ouster-ros/include/ouster_ros/os_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -126,6 +126,27 @@ void scan_to_cloud_f(ouster::PointsF& points,
const ouster::LidarScan& lidar_scan,
ouster_ros::Cloud& cloud, int return_index);

/**
* Populate a destaggered PCL point cloud from a LidarScan
* @param[out] cloud output pcl pointcloud to populate
* @param[in, out] points The points parameters is used to store the results of
* the cartesian product before it gets packed into the cloud object.
* @param[in] lut_direction the direction of the xyz lut (with single precision)
* @param[in] lut_offset the offset of the xyz lut (with single precision)
* @param[in] scan_ts scan start used to caluclate relative timestamps for
* points
* @param[in] lidar_scan input lidar data
* @param[in] pixel_shift_by_row pixel shifts by row
* @param[in] return_index index of return desired starting at 0
*/
void scan_to_cloud_f_destaggered(ouster_ros::Cloud& cloud,
ouster::PointsF& points,
const ouster::PointsF& lut_direction,
const ouster::PointsF& lut_offset, uint64_t scan_ts,
const ouster::LidarScan& ls,
const std::vector<int>& pixel_shift_by_row,
int return_index);

/**
* Serialize a PCL point cloud to a ROS message
* @param[in] cloud the PCL point cloud to convert
Expand Down
2 changes: 1 addition & 1 deletion ouster-ros/launch/record.independent.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
description="file name to use for the recorded bag file"/>
<arg name="viz" default="true"
description="whether to run a rviz"/>
<arg name="rviz_config" default="$(find-pkg-share ouster_ros)/config/viz.rviz"
<arg name="rviz_config" default="$(find-pkg-share ouster_ros)/config/viz-reliable.rviz"
description="optional rviz config file"/>

<arg name="sensor_frame" default="os_sensor"
Expand Down
2 changes: 1 addition & 1 deletion ouster-ros/launch/replay.independent.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
description="file name to use for the recorded bag file"/>
<arg name="viz" default="true"
description="whether to run a rviz"/>
<arg name="rviz_config" default="$(find-pkg-share ouster_ros)/config/viz.rviz"
<arg name="rviz_config" default="$(find-pkg-share ouster_ros)/config/viz-reliable.rviz"
description="optional rviz config file"/>

<arg name="sensor_frame" default="os_sensor"
Expand Down
2 changes: 1 addition & 1 deletion ouster-ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ouster_ros</name>
<version>0.10.0</version>
<version>0.10.1</version>
<description>Ouster ROS2 driver</description>
<maintainer email="[email protected]">ouster developers</maintainer>
<license file="LICENSE">BSD</license>
Expand Down
8 changes: 6 additions & 2 deletions ouster-ros/src/imu_packet_handler.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@
#include "ouster_ros/os_ros.h"
// clang-format on

namespace ouster_ros {

class ImuPacketHandler {
public:
using HandlerOutput = sensor_msgs::msg::Imu;
Expand All @@ -33,8 +35,10 @@ class ImuPacketHandler {
return rclcpp::Time(pf.imu_gyro_ts(imu_buf)); }};
// clang-format on
return [&pf, &frame, timestamper](const uint8_t* imu_buf) {
return ouster_ros::packet_to_imu_msg(pf, timestamper(imu_buf),
return packet_to_imu_msg(pf, timestamper(imu_buf),
frame, imu_buf);
};
}
};
};

} // namespace ouster_ros
8 changes: 5 additions & 3 deletions ouster-ros/src/laser_scan_processor.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@
#include "ouster_ros/os_ros.h"
// clang-format on

using ouster_ros::get_n_returns;
using ouster_ros::lidar_scan_to_laser_scan_msg;

namespace ouster_ros {

class LaserScanProcessor {
public:
Expand Down Expand Up @@ -64,4 +64,6 @@ class LaserScanProcessor {
uint16_t ring_;
OutputType scan_msgs;
PostProcessingFn post_processing_fn;
};
};

} // namespace ouster_ros
6 changes: 5 additions & 1 deletion ouster-ros/src/lidar_packet_handler.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,8 @@ inline bool check_token(const std::set<std::string>& tokens,

} // namespace

namespace ouster_ros {

namespace sensor = ouster::sensor;

using LidarScanProcessor = std::function<void(const ouster::LidarScan&,
Expand Down Expand Up @@ -283,4 +285,6 @@ class LidarPacketHandler {
std::vector<LidarScanProcessor> lidar_scan_handlers;

LidarPacketAccumlator lidar_packet_accumlator;
};
};

} // namespace ouster_ros
Loading

0 comments on commit 5fd074e

Please sign in to comment.