Class SensorTins

Inheritance Relationships

Base Type

Class Documentation

class SensorTins : public ros2_ouster::SensorInterface

Public Functions

SensorTins()

Default constructor.

~SensorTins()

Default destructor.

virtual void reset(ros2_ouster::Configuration &config, rclcpp_lifecycle::LifecycleNode::SharedPtr node) override

Reset lidar sensor.

Parameters:
  • configuration – file to use

  • node – pointer to the driver node, which provides access to ROS params

virtual void configure(ros2_ouster::Configuration &config, rclcpp_lifecycle::LifecycleNode::SharedPtr node) override

Configure lidar sensor.

Parameters:
  • configuration – file to use

  • node – pointer to the driver node, which provides access to ROS params

virtual ros2_ouster::Metadata getMetadata() override

Get lidar sensor’s metadata.

Returns:

sensor metadata struct

virtual ouster::sensor::client_state get() override

Ask sensor to get its current state for data collection.

Returns:

the state enum value

virtual bool readLidarPacket(const ouster::sensor::client_state &state, uint8_t *buf) override

reading a lidar packet

Parameters:
  • state – of the sensor

  • buf – pointer to a buffer to hold the packet data. Must hold getPacketFormat().lidar_packet_size bytes.

Returns:

true if a packet was recieved, false otherwise

virtual bool readImuPacket(const ouster::sensor::client_state &state, uint8_t *buf) override

reading an imu packet

Parameters:
  • state – of the sensor

  • buf – pointer to a buffer to hold the packet data. Must hold getPacketFormat().imu_packet_size bytes.

Returns:

true if a packet was recieved, false otherwise

void setMetadata(int lidar_port, int imu_port, const std::string &timestamp_mode)

Sets the metadata class variable.

Parameters:
  • lidar_port

  • imu_port

virtual ouster::sensor::packet_format getPacketFormat() override

Get lidar sensor’s packet format.

Returns:

packet format struct

void loadSensorInfoFromJsonFile(const std::string filepath_to_read, ouster::sensor::sensor_info &sensor_info)

Load metadata from a file.

Some important notes about this function: This populates an ouster::sensor::sensor_info object, but the more commonly used ros2_ouster::Metadata object has some additional parameters that must be sourced elsewhere. Also note that the underlying Ouster library is inconsistent in what parameters must be provided in the JSON file vs what will be silently set to a default value if not provided.

Parameters:
  • filepath_to_read[in] A fully qualified filepath to a yaml file containing the parameters to load

  • sensor_info[out] The metadata to load data into.

void initializeSniffer(const std::string eth_device)

Initializes the internal Tins::Sniffer object.

Parameters:

eth_device[in] The name of the ethernet device for the sniffer to listen to. This is typically a device like “eth0”, “eth1” or “eno0”

bool sniffOnePacket(Tins::Packet &packet)

sniff for one packet and one packet only. If a valid LiDAR or IMU packet is found, it will set the internal _replay_state to client_state::LIDAR_DATA or client_state::IMU_DATA

This function is intended to only be used as a callback for the sniffer->sniff_loop function

Parameters:

packet[in] The input packet from the tins sniffer to parse.

Returns:

False if the packet is an Ouster LiDAR or IMU packet, in which case we don’t want to continue sniffing, and want sniff_loop to stop. True if the packets aren’t good and we need to continue looking.