Classes | Typedefs | Enumerations | Functions | Variables
ouster::OS1 Namespace Reference

Classes

struct  client
 

Typedefs

using ns = std::chrono::nanoseconds
 
using OperationMode = operation_mode_t
 
using PulseMode = pulse_mode_t
 

Enumerations

enum  client_state { ERROR = 1, LIDAR_DATA = 2, IMU_DATA = 4 }
 
enum  operation_mode_t {
  MODE_512x10 =0, MODE_1024x10 =1, MODE_2048x10 =2, MODE_512x20 =3,
  MODE_1024x20 =4
}
 
enum  pulse_mode_t { PULSE_STANDARD =0, PULSE_NARROW =1 }
 

Functions

static int cfg_socket (const char *addr)
 
float col_h_angle (const uint8_t *col_buf)
 
float col_h_encoder_count (const uint8_t *col_buf)
 
uint32_t col_measurement_id (const uint8_t *col_buf)
 
uint64_t col_timestamp (const uint8_t *col_buf)
 
uint32_t col_valid (const uint8_t *col_buf)
 
uint64_t imu_accel_ts (const uint8_t *imu_buf)
 
float imu_av_x (const uint8_t *imu_buf)
 
float imu_av_y (const uint8_t *imu_buf)
 
float imu_av_z (const uint8_t *imu_buf)
 
uint64_t imu_gyro_ts (const uint8_t *imu_buf)
 
float imu_la_x (const uint8_t *imu_buf)
 
float imu_la_y (const uint8_t *imu_buf)
 
float imu_la_z (const uint8_t *imu_buf)
 
uint64_t imu_sys_ts (const uint8_t *imu_buf)
 
std::shared_ptr< clientinit_client (const std::string &hostname, const std::string &udp_dest_host, int lidar_port, int imu_port)
 
static bool init_tables ()
 
const uint8_t * nth_col (int n, const uint8_t *udp_buf)
 
const uint8_t * nth_px (int n, const uint8_t *col_buf)
 
client_state poll_client (const client &cli)
 
uint16_t px_noise_photons (const uint8_t *px_buf)
 
uint32_t px_range (const uint8_t *px_buf)
 
uint16_t px_reflectivity (const uint8_t *px_buf)
 
uint16_t px_signal_photons (const uint8_t *px_buf)
 
bool read_imu_packet (const client &cli, uint8_t *buf)
 
bool read_lidar_packet (const client &cli, uint8_t *buf)
 
static bool recv_fixed (int fd, void *buf, size_t len)
 
void set_advanced_params (std::string operation_mode_str, std::string pulse_mode_str, bool window_rejection)
 
static int udp_data_socket (int port)
 

Variables

static OperationMode _operation_mode = ouster::OS1::MODE_1024x10
 
static std::string _operation_mode_str = ""
 
static PulseMode _pulse_mode = ouster::OS1::PULSE_STANDARD
 
static std::string _pulse_mode_str = ""
 
static bool _window_rejection = true
 
static std::string _window_rejection_str = ""
 
const size_t imu_packet_bytes = 48
 
const size_t lidar_packet_bytes = 12608
 
static bool tables_initialized = init_tables()
 

Typedef Documentation

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

Definition at line 21 of file os1.cpp.

Definition at line 72 of file os1.h.

Definition at line 81 of file os1.h.

Enumeration Type Documentation

Enumerator
ERROR 
LIDAR_DATA 
IMU_DATA 

Definition at line 19 of file os1.h.

Operation modes (horizontal resolution and scan rate) supported by the OS1 LiDAR

Enumerator
MODE_512x10 
MODE_1024x10 
MODE_2048x10 
MODE_512x20 
MODE_1024x20 

Definition at line 65 of file os1.h.

Laser pulse modes supported by the OS1 LiDAR

Enumerator
PULSE_STANDARD 
PULSE_NARROW 

Definition at line 77 of file os1.h.

Function Documentation

static int ouster::OS1::cfg_socket ( const char *  addr)
static

Definition at line 73 of file os1.cpp.

float ouster::OS1::col_h_angle ( const uint8_t *  col_buf)
inline

Definition at line 78 of file os1_packet.h.

float ouster::OS1::col_h_encoder_count ( const uint8_t *  col_buf)
inline

Definition at line 84 of file os1_packet.h.

uint32_t ouster::OS1::col_measurement_id ( const uint8_t *  col_buf)
inline

Definition at line 90 of file os1_packet.h.

uint64_t ouster::OS1::col_timestamp ( const uint8_t *  col_buf)
inline

Definition at line 72 of file os1_packet.h.

uint32_t ouster::OS1::col_valid ( const uint8_t *  col_buf)
inline

Definition at line 96 of file os1_packet.h.

uint64_t ouster::OS1::imu_accel_ts ( const uint8_t *  imu_buf)
inline

Definition at line 139 of file os1_packet.h.

float ouster::OS1::imu_av_x ( const uint8_t *  imu_buf)
inline

Definition at line 171 of file os1_packet.h.

float ouster::OS1::imu_av_y ( const uint8_t *  imu_buf)
inline

Definition at line 177 of file os1_packet.h.

float ouster::OS1::imu_av_z ( const uint8_t *  imu_buf)
inline

Definition at line 183 of file os1_packet.h.

uint64_t ouster::OS1::imu_gyro_ts ( const uint8_t *  imu_buf)
inline

Definition at line 145 of file os1_packet.h.

float ouster::OS1::imu_la_x ( const uint8_t *  imu_buf)
inline

Definition at line 152 of file os1_packet.h.

float ouster::OS1::imu_la_y ( const uint8_t *  imu_buf)
inline

Definition at line 158 of file os1_packet.h.

float ouster::OS1::imu_la_z ( const uint8_t *  imu_buf)
inline

Definition at line 164 of file os1_packet.h.

uint64_t ouster::OS1::imu_sys_ts ( const uint8_t *  imu_buf)
inline

Definition at line 133 of file os1_packet.h.

std::shared_ptr< client > ouster::OS1::init_client ( const std::string &  hostname,
const std::string &  udp_dest_host,
int  lidar_port,
int  imu_port 
)

Connect to the sensor and start listening for data

Parameters
hostnamehostname or ip of the sensor
udp_dest_hosthostname or ip where the sensor should send data
lidar_portport on which the sensor will send lidar data
imu_portport on which the sensor will send imu data
Returns
pointer owning the resources associated with the connection
Note
Added to support advanced mode parameters configuration
Added to support advanced mode parameters configuration

Definition at line 114 of file os1.cpp.

static bool ouster::OS1::init_tables ( )
static

Definition at line 56 of file os1_packet.h.

const uint8_t* ouster::OS1::nth_col ( int  n,
const uint8_t *  udp_buf 
)
inline

Definition at line 68 of file os1_packet.h.

const uint8_t* ouster::OS1::nth_px ( int  n,
const uint8_t *  col_buf 
)
inline

Definition at line 103 of file os1_packet.h.

client_state ouster::OS1::poll_client ( const client cli)

Block for up to a second until either data is ready or an error occurs.

Parameters
cliclient returned by init_client associated with the connection
Returns
client_state s where (s & ERROR) is true if an error occured, (s & LIDAR_DATA) is true if lidar data is ready to read, and (s & IMU_DATA) is true if imu data is ready to read

Definition at line 279 of file os1.cpp.

uint16_t ouster::OS1::px_noise_photons ( const uint8_t *  px_buf)
inline

Definition at line 126 of file os1_packet.h.

uint32_t ouster::OS1::px_range ( const uint8_t *  px_buf)
inline

Definition at line 107 of file os1_packet.h.

uint16_t ouster::OS1::px_reflectivity ( const uint8_t *  px_buf)
inline

Definition at line 114 of file os1_packet.h.

uint16_t ouster::OS1::px_signal_photons ( const uint8_t *  px_buf)
inline

Definition at line 120 of file os1_packet.h.

bool ouster::OS1::read_imu_packet ( const client cli,
uint8_t *  buf 
)

Read imu data from the sensor. Will block for up to a second if no data is available.

Parameters
cliclient returned by init_client associated with the connection
bufbuffer to which to write imu data. Must be at least imu_packet_bytes + 1 bytes
Returns
true if an imu packet was successfully read

Definition at line 315 of file os1.cpp.

bool ouster::OS1::read_lidar_packet ( const client cli,
uint8_t *  buf 
)

Read lidar data from the sensor. Will block for up to a second if no data is available.

Parameters
cliclient returned by init_client associated with the connection
bufbuffer to which to write lidar data. Must be at least lidar_packet_bytes + 1 bytes
Returns
true if a lidar packet was successfully read

Definition at line 311 of file os1.cpp.

static bool ouster::OS1::recv_fixed ( int  fd,
void *  buf,
size_t  len 
)
static

Definition at line 300 of file os1.cpp.

void ouster::OS1::set_advanced_params ( std::string  operation_mode_str,
std::string  pulse_mode_str,
bool  window_rejection 
)

Define the pointcloud type to use

Parameters
operation_modedefines the resolution and frame rate
pulse_modeis the width of the laser pulse (standard or narrow)
window_rejectionto reject short range data (true), or to accept short range data (false)
Note
This function was added to configure advanced operation modes for Autoware
Added to support advanced mode parameters configuration for Autoware

Definition at line 323 of file os1.cpp.

static int ouster::OS1::udp_data_socket ( int  port)
static

Definition at line 43 of file os1.cpp.

Variable Documentation

OperationMode ouster::OS1::_operation_mode = ouster::OS1::MODE_1024x10
static
Note
Added to support advanced mode parameters configuration for Autoware

Definition at line 26 of file os1.cpp.

std::string ouster::OS1::_operation_mode_str = ""
static

Definition at line 29 of file os1.cpp.

PulseMode ouster::OS1::_pulse_mode = ouster::OS1::PULSE_STANDARD
static

Definition at line 27 of file os1.cpp.

std::string ouster::OS1::_pulse_mode_str = ""
static

Definition at line 30 of file os1.cpp.

bool ouster::OS1::_window_rejection = true
static

Definition at line 28 of file os1.cpp.

std::string ouster::OS1::_window_rejection_str = ""
static

Definition at line 31 of file os1.cpp.

const size_t ouster::OS1::imu_packet_bytes = 48

Definition at line 15 of file os1.h.

const size_t ouster::OS1::lidar_packet_bytes = 12608

Definition at line 14 of file os1.h.

bool ouster::OS1::tables_initialized = init_tables()
static

Definition at line 65 of file os1_packet.h.



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