Classes | Typedefs | Functions | Variables
ouster_driver::OS1 Namespace Reference

Classes

struct  PointOS1
 
struct  PointXYZIF
 
struct  PointXYZIFN
 
struct  PointXYZIR
 
struct  PointXYZIRF
 
struct  PointXYZIRFN
 

Typedefs

using CloudOS1 = pcl::PointCloud< PointOS1 >
 
using CloudOS1XYZ = pcl::PointCloud< pcl::PointXYZ >
 
using CloudOS1XYZI = pcl::PointCloud< pcl::PointXYZI >
 
using CloudOS1XYZIF = pcl::PointCloud< PointXYZIF >
 
using CloudOS1XYZIFN = pcl::PointCloud< PointXYZIFN >
 
using CloudOS1XYZIR = pcl::PointCloud< PointXYZIR >
 
using CloudOS1XYZIRF = pcl::PointCloud< PointXYZIRF >
 
using CloudOS1XYZIRFN = pcl::PointCloud< PointXYZIRFN >
 
using ns = std::chrono::nanoseconds
 

Functions

void add_packet_to_cloud (ns scan_start_ts, ns scan_duration, const PacketMsg &pm, CloudOS1 &cloud)
 
std::function< void(const PacketMsg &)> batch_packets (ns scan_dur, const std::function< void(ns, const CloudOS1 &)> &f)
 
sensor_msgs::PointCloud2 cloud_to_cloud_msg (const CloudOS1 &cloud, ns timestamp, const std::string &frame="os1")
 
void convert2XYZ (const CloudOS1 &in, CloudOS1XYZ &out)
 
void convert2XYZI (const CloudOS1 &in, CloudOS1XYZI &out)
 
void convert2XYZIF (const CloudOS1 &in, CloudOS1XYZIF &out)
 
void convert2XYZIFN (const CloudOS1 &in, CloudOS1XYZIFN &out)
 
void convert2XYZIR (const CloudOS1 &in, CloudOS1XYZIR &out)
 
void convert2XYZIRF (const CloudOS1 &in, CloudOS1XYZIRF &out)
 
void convert2XYZIRFN (const CloudOS1 &in, CloudOS1XYZIRFN &out)
 
static ns nearest_scan_dur (ns scan_dur, ns ts)
 
static PointOS1 nth_point (int ind, const uint8_t *col_buf)
 
sensor_msgs::Imu packet_to_imu_msg (const PacketMsg &pm, const std::string &frame="os1_imu")
 
bool read_imu_packet (const ouster::OS1::client &cli, PacketMsg &pm)
 
bool read_lidar_packet (const ouster::OS1::client &cli, PacketMsg &pm)
 
void set_point_mode (std::string mode_xyzir)
 
void spin (const ouster::OS1::client &cli, const std::function< void(const PacketMsg &pm)> &lidar_handler, const std::function< void(const PacketMsg &pm)> &imu_handler)
 
ns timestamp_of_imu_packet (const PacketMsg &pm)
 
ns timestamp_of_lidar_packet (const PacketMsg &pm)
 

Variables

static std::string _pointcloud_mode = "NATIVE"
 
std::function< void(const PacketMsg &)> batch_packets (ns scan_dur, const std::function< void(ns, const CloudOS1 &)> &f)
 

Typedef Documentation

Definition at line 23 of file os1_ros.h.

using ouster_driver::OS1::CloudOS1XYZ = typedef pcl::PointCloud<pcl::PointXYZ>

Definition at line 24 of file os1_ros.h.

using ouster_driver::OS1::CloudOS1XYZI = typedef pcl::PointCloud<pcl::PointXYZI>

Definition at line 25 of file os1_ros.h.

Definition at line 27 of file os1_ros.h.

Definition at line 29 of file os1_ros.h.

Definition at line 26 of file os1_ros.h.

Definition at line 28 of file os1_ros.h.

Definition at line 30 of file os1_ros.h.

using ouster_driver::OS1::ns = typedef std::chrono::nanoseconds

Definition at line 31 of file os1_ros.h.

Function Documentation

void ouster_driver::OS1::add_packet_to_cloud ( ns  scan_start_ts,
ns  scan_duration,
const PacketMsg pm,
CloudOS1 cloud 
)

Accumulate points from a lidar packet message into a PCL point cloud. All points are timestamped relative to scan_start_ts as a fraction of scan_duration, a float usually [0.0, 1.0)

Parameters
scan_start_tsthe timestamp of the beginning of the batch
scan_durationlength of a scan used to compute point timestamps
pmpacket message populated by read_lidar_packet
cloudPCL point cloud of PointOS1s to accumulate

Definition at line 137 of file os1_ros.cpp.

std::function<void(const PacketMsg&)> ouster_driver::OS1::batch_packets ( ns  scan_dur,
const std::function< void(ns, const CloudOS1 &)> &  f 
)

Definition at line 182 of file os1_ros.cpp.

sensor_msgs::PointCloud2 ouster_driver::OS1::cloud_to_cloud_msg ( const CloudOS1 cloud,
ns  timestamp,
const std::string &  frame = "os1" 
)

Serialize a PCL point cloud to a ROS message

Parameters
cloudthe PCL point cloud to convert
timestampthe timestamp to give the resulting ROS message
framethe frame to set in the resulting ROS message
Returns
a ROS message containing the point cloud. Can be deserialized with fromROSMsg in pcl_conversions
Note
Added to support Velodyne compatible pointcloud format for Autoware
Changed timestamp from LiDAR to ROS time for Autoware operation
Added to support Velodyne compatible pointcloud format for Autoware
Changed timestamp from LiDAR to ROS time for Autoware operation

Definition at line 70 of file os1_ros.cpp.

void ouster_driver::OS1::convert2XYZ ( const CloudOS1 in,
CloudOS1XYZ out 
)

Converts the OS1 native point format to XYZ

Definition at line 212 of file os1_ros.cpp.

void ouster_driver::OS1::convert2XYZI ( const CloudOS1 in,
CloudOS1XYZI out 
)

Converts the OS1 native point format to XYZI

Definition at line 224 of file os1_ros.cpp.

void ouster_driver::OS1::convert2XYZIF ( const CloudOS1 in,
CloudOS1XYZIF out 
)

Converts the OS1 native point format to XYZIF (with intensity and reflectivity)

Note
Extract intensity and reflectivity data

Definition at line 257 of file os1_ros.cpp.

void ouster_driver::OS1::convert2XYZIFN ( const CloudOS1 in,
CloudOS1XYZIFN out 
)

Converts the OS1 native point format to XYZIFN (with intensity, reflectivity and ambient noise)

Note
Extract intensity, reflectivity and ambient noise data

Definition at line 292 of file os1_ros.cpp.

void ouster_driver::OS1::convert2XYZIR ( const CloudOS1 in,
CloudOS1XYZIR out 
)

Converts the OS1 native point format to XYZIR (Velodyne like)

Note
Added to support Velodyne compatible pointcloud format for Autoware

Definition at line 240 of file os1_ros.cpp.

void ouster_driver::OS1::convert2XYZIRF ( const CloudOS1 in,
CloudOS1XYZIRF out 
)

Converts the OS1 native point format to XYZIRF (with intensity, ring and reflectivity)

Note
Extract intensity, ring and reflectivity data

Definition at line 274 of file os1_ros.cpp.

void ouster_driver::OS1::convert2XYZIRFN ( const CloudOS1 in,
CloudOS1XYZIRFN out 
)

Converts the OS1 native point format to XYZIRFN (with intensity, ring, reflectivity and ambient noise)

Note
Extract intensity, ring, reflectivity and ambient noise data

Definition at line 310 of file os1_ros.cpp.

static ns ouster_driver::OS1::nearest_scan_dur ( ns  scan_dur,
ns  ts 
)
static

Definition at line 178 of file os1_ros.cpp.

static PointOS1 ouster_driver::OS1::nth_point ( int  ind,
const uint8_t *  col_buf 
)
static

Definition at line 119 of file os1_ros.cpp.

sensor_msgs::Imu ouster_driver::OS1::packet_to_imu_msg ( const PacketMsg pm,
const std::string &  frame = "os1_imu" 
)

Parse an imu packet message into a ROS imu message

Parameters
pmpacket message populated by read_imu_packet
framethe frame to set in the resulting ROS message
Returns
ROS sensor message with fields populated from the OS1 packet
Note
Modified to support custom message frame name
Note
Modified to support custom message frame name
Modified to support custom message frame name

Definition at line 32 of file os1_ros.cpp.

bool ouster_driver::OS1::read_imu_packet ( const ouster::OS1::client cli,
PacketMsg pm 
)

Read an imu packet into a ROS message. Blocks for up to a second if no data is available.

Parameters
clithe OS1 client
pmthe destination packet message
Returns
whether reading was successful

Definition at line 22 of file os1_ros.cpp.

bool ouster_driver::OS1::read_lidar_packet ( const ouster::OS1::client cli,
PacketMsg pm 
)

Read a lidar packet into a ROS message. Blocks for up to a second if no data is available.

Parameters
clithe OS1 client
pmthe destination packet message
Returns
whether reading was successful

Definition at line 27 of file os1_ros.cpp.

void ouster_driver::OS1::set_point_mode ( std::string  mode_xyzir)

Define the pointcloud type to use

Parameters
mode_xyzirspecifies the point cloud type to publish supported values: NATIVE, XYZ, XYZI, XYZIR, XYZIF, XYZIFN
Note
Added to support Velodyne compatible pointcloud format for Autoware

Definition at line 207 of file os1_ros.cpp.

void ouster_driver::OS1::spin ( const ouster::OS1::client cli,
const std::function< void(const PacketMsg &pm)> &  lidar_handler,
const std::function< void(const PacketMsg &pm)> &  imu_handler 
)

Loop reading from the OS1 client and invoking callbacks with packet messages. Returns when ROS exits. Also runs the ROS event loop via ros::spinOnce().

Parameters
clithe OS1 client
lidar_handlercallback invoked with messages populated by read_lidar_packet
imu_handlercallback invoked with messages populated by read_imu_packet

Definition at line 153 of file os1_ros.cpp.

ns ouster_driver::OS1::timestamp_of_imu_packet ( const PacketMsg pm)

Read a timestamp from an imu packet message

Parameters
clithe OS1 client
pmpacket message populated by read_imu_packet
Returns
timestamp in nanoseconds

Definition at line 14 of file os1_ros.cpp.

ns ouster_driver::OS1::timestamp_of_lidar_packet ( const PacketMsg pm)

Read a timestamp from a lidar packet message

Parameters
pmpacket message populated by read_lidar_packet
Returns
timestamp in nanoseconds

Definition at line 18 of file os1_ros.cpp.

Variable Documentation

std::string ouster_driver::OS1::_pointcloud_mode = "NATIVE"
static

Definition at line 12 of file os1_ros.cpp.

std::function<void(const PacketMsg&)> ouster_driver::OS1::batch_packets(ns scan_dur, const std::function< void(ns, const CloudOS1 &)> &f)

Construct a function that will batch packets into a PCL point cloud for the given duration, then invoke f with the complete cloud.

Parameters
scan_durduration to batch packets in nanoseconds
fa callback taking a PCL pointcloud to invoke on a complete batch
Returns
a function that batches packet messages populated by read_lidar_packet and invokes f on the result

Definition at line 120 of file os1_ros.h.



ouster
Author(s): ouster developers
autogenerated on Mon Jun 10 2019 14:16:21