how_to_decode_pcap_file.md 5.6 KB

How to decode PCAP file

1 Introduction

Before reading this document, please be sure that you have read Decode online Lidar.

The PCAP file is captured with some 3rd party tools, such as Wireshark/tcpdump.

This document illustrates how to decode it with the driver's API.

2 Steps

Below is the steps to use the driver's API.

2.1 Define Point Type

Point is the base unit of Point Cloud. The driver supposes that it may have these member variables.

  • x -- float type. The x coordinate of point.
  • y -- float type. The y coordinate of point.
  • z -- float type. The z coordinate of point.
  • intensity -- uint8_t type. The intensity of point.
  • timestamp -- double type. The timestamp of point. It may generated by the Lidar or on the host machine.
  • ring -- The ring ID of the point, which represents the row number. e.g. For RS80, the range of ring ID is 0~79 (from bottom to top).

Below are some examples:

  • The point type contains x, y, z, intensity
  struct PointXYZI
  {
    float x;
    float y;
    float z;
    uint8_t intensity;
    ...
  };
  • If using PCL, a simple way is to use pcl::PointXYZI.

  • The point type contains x, y, z, intensity, timestamp, ring

  struct PointXYZIRT
  {
    float x;
    float y;
    float z;
    uint8_t intensity;
    double timestamp;
    uint16_t ring;
    ...
  };

Here user may add new member variables, remove member variables, or change the order of them, but should not change names or types of them, otherwise the behaviors might be unexpected.

2.2 Define Point Cloud

The driver allows user to change the point cloud type, as long as it is compatible to the definition below.

  template <typename T_Point>
  class PointCloudT
  {
  public:
    typedef T_Point PointT;
    typedef std::vector<PointT> VectorT;

    uint32_t height = 0;    ///< Height of point cloud
    uint32_t width = 0;     ///< Width of point cloud
    bool is_dense = false;  ///< If is_dense is true, the point cloud does not contain NAN points
    double timestamp = 0.0; ///< Timestamp of point cloud
    uint32_t seq = 0;       ///< Sequence number of message

    VectorT points;
  };
  
  typedef PointXYZI PointT;
  typedef PointCloudT<PointT> PointCloudMsg;

Here user may add new members, and change the order of these members, but should not change or remove them.

2.3 Define the driver object

Define a driver object.

int main()
{
  LidarDriver<PointCloudMsg> driver;          ///< Declare the driver object
  ...
}

2.4 Configure the driver parameter

Define a RSDriverParam variable and configure it.

  • InputType::PCAP_FILE means that the driver get packets from a PCAP file, which is /home/robosense/lidar.pcap.
  • LidarType::RS16 means a RS16 Lidar.
  • Also set the local MSOP/DIFOP ports. Please use a 3rd party tool, such as Wireshark, to get them.
int main()
{
  ...
  RSDriverParam param;                             ///< Create a parameter object
  param.input_type = InputType::PCAP_FILE;         /// get packet from the pcap file 
  param.input_param.pcap_path = "/home/robosense/lidar.pcap";  ///< Set the pcap file path
  param.input_param.msop_port = 6699;             ///< Set the lidar msop port number, the default is 6699
  param.input_param.difop_port = 7788;            ///< Set the lidar difop port number, the default is 7788
  param.lidar_type = LidarType::RS16;             ///< Set the lidar type. Make sure this type is correct
  ...
}

2.5 Define and register Point Cloud callbacks

User is supposed to provide free point cloud to the driver.

std::shared_ptr<PointCloudMsg> pointCloudGetCallback(void)
{
  return std::make_shared<PointCloudMsg>();
}

Also user is supposed to accept stuffed point cloud from the driver.

void pointCloudPutCallback(std::shared_ptr<PointCloudMsg> msg)
{
  RS_MSG << "msg: " << msg->seq << " point cloud size: " << msg->points.size() << RS_REND;
}

Note: The driver parses packet and constructs point cloud in its own thread. It also calls these two callback functions in this thread , so don't do any time-consuming task in them.

Register the callbacks to the driver.

int main()
{
  ...
  driver.regPointCloudCallback(pointCloudGetCallback, pointCloudPutCallback); ///< Register the point cloud callback functions
  ...
}

2.6 Define and register exception callbacks

When an error happens, the driver will inform user. User is supposed to accept it.

void exceptionCallback(const Error &code)
{
  RS_WARNING << "Error code : " << code.toString() << RS_REND;
}

Once again, don't do any time-consuming task in it.

Register the callback.

int main()
{
  ...
  driver.regExceptionCallback(exceptionCallback);  ///<Register the exception callback function
  ...
}

2.7 Initialize the driver

Call the initialization function with the the RSDriverParam object.

int main()
{
  ...
  if (!driver.init(param))                         ///< Call the init function and pass the parameter
  {
    RS_ERROR << "Driver Initialize Error..." << RS_REND;
    return -1;
  }
  ...
}

Please register call callback functions before call init(), because errors may occur during the initialization.

2.8 Start the driver

Start the driver.

int main()
{
  ...
  driver.start();                                  ///< Call the start function. The driver thread will start
  ...
}

3 Congratulations

You have finished the demo tutorial of the RoboSense LiDAR driver!

Please find the complete demo code rs_driver/demo/demo_pcap.cpp in the project directory.

Feel free to contact us if you have any questions.