client.h
Client Initialization
-
std::shared_ptr<client> init_client(const std::string &hostname, int lidar_port, int imu_port)
Listen for sensor data on the specified ports; do not configure the sensor.
- Parameters
hostname – [in] The hostname to connect to.
lidar_port – [in] port on which the sensor will send lidar data.
imu_port – [in] port on which the sensor will send imu data.
- Returns
pointer owning the resources associated with the connection.
-
std::shared_ptr<client> init_client(const std::string &hostname, const std::string &udp_dest_host, lidar_mode ld_mode = MODE_UNSPEC, timestamp_mode ts_mode = TIME_FROM_UNSPEC, int lidar_port = 0, int imu_port = 0, int timeout_sec = DEFAULT_HTTP_REQUEST_TIMEOUT_SECONDS)
Connect to and configure the sensor and start listening for data.
- Parameters
hostname – [in] hostname or ip of the sensor.
udp_dest_host – [in] hostname or ip where the sensor should send data or “” for automatic detection of destination.
ld_mode – [in] The lidar mode to use.
ts_mode – [in] The timestamp mode to use.
lidar_port – [in] port on which the sensor will send lidar data. When using zero the method will automatically acquire and assign any free port.
imu_port – [in] port on which the sensor will send imu data. When using zero the method will automatically acquire and assign any free port.
timeout_sec – [in] how long to wait for the sensor to initialize.
- Returns
pointer owning the resources associated with the connection.
-
std::shared_ptr<client> mtp_init_client(const std::string &hostname, const sensor_config &config, const std::string &mtp_dest_host, bool main, int timeout_sec = DEFAULT_HTTP_REQUEST_TIMEOUT_SECONDS)
[BETA] Connect to and configure the sensor and start listening for data via multicast.
- Remark
when main flag is set the config object will be used to configure the sensor, otherwise only the port values within the config object will be used and the rest will be ignored.
- Parameters
hostname – [in] hostname or ip of the sensor.
config – [in] sensor config to set on sensor.
mtp_dest_host – [in] multicast ip address where the sensor should send data.
main – [in] a flag that indicates this is the main connection to the sensor in an multicast setup.
timeout_sec – [in] how long to wait for the sensor to initialize.
- Returns
pointer owning the resources associated with the connection.
Data Fetching
-
client_state ouster::sensor::poll_client(const client &cli, int timeout_sec = 1)
Block for up to timeout_sec until either data is ready or an error occurs.
NOTE: will return immediately if LIDAR_DATA or IMU_DATA are set and not cleared by read_lidar_data() and read_imu_data() before the next call.
- Parameters
cli – [in] client returned by init_client associated with the connection.
timeout_sec – [in] seconds to block while waiting for data.
- 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.
-
bool ouster::sensor::read_lidar_packet(const client &cli, uint8_t *buf, const packet_format &pf)
Read lidar data from the sensor. Will not block.
- Parameters
cli – [in] client returned by init_client associated with the connection.
buf – [out] buffer to which to write lidar data. Must be at least lidar_packet_bytes + 1 bytes.
pf – [in] The packet format.
- Returns
true if a lidar packet was successfully read.
-
bool ouster::sensor::read_imu_packet(const client &cli, uint8_t *buf, const packet_format &pf)
Read imu data from the sensor. Will not block.
- Parameters
cli – [in] client returned by init_client associated with the connection.
buf – [out] buffer to which to write imu data. Must be at least imu_packet_bytes + 1 bytes.
pf – [in] The packet format.
- Returns
true if an imu packet was successfully read.
Config And Metadata
-
std::string ouster::sensor::get_metadata(client &cli, int timeout_sec = DEFAULT_HTTP_REQUEST_TIMEOUT_SECONDS, bool legacy_format = false)
Get metadata text blob from the sensor.
Will attempt to fetch from the network if not already populated.
- Throws
runtime_error – if the sensor is in ERROR state, the firmware version used to initialize the HTTP or TCP client is invalid, the metadata could not be retrieved from the sensor within the timeout period, a timeout occured while waiting for the sensor to finish initializing, or the response could not be parsed.
- Parameters
cli – [in] client returned by init_client associated with the connection.
timeout_sec – [in] how long to wait for the sensor to initialize.
legacy_format – [in] whether to use legacy format of metadata output.
- Returns
a text blob of metadata parseable into a sensor_info struct.
-
bool ouster::sensor::get_config(const std::string &hostname, sensor_config &config, bool active = true, int timeout_sec = DEFAULT_HTTP_REQUEST_TIMEOUT_SECONDS)
Get sensor config from the sensor.
Populates passed in config with the results of get_config.
- Parameters
hostname – [in] sensor hostname.
config – [out] sensor config to populate.
active – [in] whether to pull active or passive configs.
- Returns
true if sensor config successfully populated.
-
bool ouster::sensor::set_config(const std::string &hostname, const sensor_config &config, uint8_t config_flags = 0, int timeout_sec = DEFAULT_HTTP_REQUEST_TIMEOUT_SECONDS)
Set sensor config on sensor.
- Throws
runtime_error – on failure to communcate with the sensor.
invalid_argument – when config parameters fail validation.
- Parameters
hostname – [in] sensor hostname.
config – [in] sensor config.
config_flags – [in] flags to pass in.
- Returns
true if config params successfuly set on sensor.
-
enum ouster::sensor::config_flags
Flags for set_config()
Values:
-
enumerator CONFIG_UDP_DEST_AUTO
Set udp_dest automatically.
-
enumerator CONFIG_PERSIST
Make configuration persistent.
-
enumerator CONFIG_FORCE_REINIT
Forces the sensor to re-init during set_config even when config params have not changed
-
enumerator CONFIG_UDP_DEST_AUTO
Network Operations
-
int ouster::sensor::get_lidar_port(client &cli)
Return the port used to listen for lidar UDP data.
- Parameters
cli – [in] client returned by init_client associated with the connection.
- Returns
the port number.
-
int ouster::sensor::get_imu_port(client &cli)
Return the port used to listen for imu UDP data.
- Parameters
cli – [in] client returned by init_client associated with the connection.
- Returns
the port number.