Template Class Decoder

Inheritance Relationships

Derived Types

Class Documentation

template<typename T_PointCloud>
class Decoder

Subclassed by robosense::lidar::DecoderMech< T_PointCloud >, robosense::lidar::DecoderRSE1< T_PointCloud >, robosense::lidar::DecoderRSM1< T_PointCloud >, robosense::lidar::DecoderRSM1_Jumbo< T_PointCloud >, robosense::lidar::DecoderRSM2< T_PointCloud >, robosense::lidar::DecoderRSM3< T_PointCloud >, robosense::lidar::DecoderRSMX< T_PointCloud >

Public Functions

virtual void decodeDifopPkt(const uint8_t *pkt, size_t size) = 0
virtual bool decodeMsopPkt(const uint8_t *pkt, size_t size) = 0
inline virtual void decodeImuPkt(const uint8_t *pkt, size_t size)
virtual ~Decoder() = default
inline void processDifopPkt(const uint8_t *pkt, size_t size)
inline bool processMsopPkt(const uint8_t *pkt, size_t size)
inline bool processImuPkt(const uint8_t *pkt, size_t size)
inline explicit Decoder(const RSDecoderConstParam &const_param, const RSDecoderParam &param)
inline bool getTemperature(float &temp)
inline bool getDeviceInfo(DeviceInfo &info)
inline bool getDeviceStatus(DeviceStatus &status)
inline double getPacketDuration()
inline void enableWritePktTs(bool value)
inline double prevPktTs()
inline void transformPoint(float &x, float &y, float &z)
inline void regCallback(const std::function<void(const Error&)> &cb_excep, const std::function<void(uint16_t, double)> &cb_split_frame)
inline void regImuCallback(const std::function<void()> &cb_imu_data)
inline virtual bool isNewFrame(const uint8_t *packet)
inline bool isNewFrameCommon(const uint8_t *packet)

Public Members

std::shared_ptr<T_PointCloud> point_cloud_
std::shared_ptr<ImuData> imuDataPtr_
SplitStrategyBySeq pre_split_strategy_comm_
bool is_mech_ = {false}

Public Static Attributes

static constexpr uint8_t PKT_SEQ_HIGH_BYTE_OFFSET = 4
static constexpr uint8_t PKT_SEQ_LOW_BYTE_OFFSET = 5

Protected Functions

inline double cloudTs()

Protected Attributes

RSDecoderConstParam const_param_
RSDecoderParam param_
std::function<void(uint16_t, double)> cb_split_frame_
std::function<void(const Error&)> cb_excep_
std::function<void()> cb_imu_data_
bool write_pkt_ts_
Trigon trigon_
double packet_duration_
DistanceSection distance_section_
RSEchoMode echo_mode_
float temperature_
DeviceInfo device_info_
DeviceStatus device_status_
bool angles_ready_
double prev_pkt_ts_
double prev_point_ts_
double first_point_ts_
bool is_get_temperature_ = {false}