Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

warning in terminal #73

Open
7DoF opened this issue Jul 20, 2023 · 2 comments
Open

warning in terminal #73

7DoF opened this issue Jul 20, 2023 · 2 comments

Comments

@7DoF
Copy link

7DoF commented Jul 20, 2023

Hi, when i run the launch file I get this message in the terminal indefinitely:
Failed to find match for field 'ring'.

Here's the info about my rosbag:

path:        calib_3.bag
version:     2.0
duration:    1:06s (66s)
start:       Jul 19 2023 15:15:13.51 (1689759913.51)
end:         Jul 19 2023 15:16:19.87 (1689759979.87)
size:        1007.3 MB
messages:    35466
compression: none [664/664 chunks]
types:       sensor_msgs/Imu         [6a62c6daae103f4ff57a132d6f95cec2]
             sensor_msgs/PointCloud2 [1158d486dd51d683ce2f1be655c3c181]
topics:      /imu0               33284 msgs    : sensor_msgs/Imu        
             /mavros/imu/data     1519 msgs    : sensor_msgs/Imu        
             /ouster_11/points     663 msgs    : sensor_msgs/PointCloud2

Thanks

@nkhedekar
Copy link

The point type for your pointcloud may be different from what is expected by this package. I would check the point fields in the pointcloud2 message and match them with the point types defined here

namespace velodyne_ros {
struct EIGEN_ALIGN16 Point {
PCL_ADD_POINT4D;
float intensity;
float time;
uint16_t ring;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
} // namespace velodyne_ros
POINT_CLOUD_REGISTER_POINT_STRUCT(velodyne_ros::Point,
(float, x, x)
(float, y, y)
(float, z, z)
(float, intensity, intensity)
(float, time, time)
(uint16_t, ring, ring)
)
namespace ouster_ros {
struct EIGEN_ALIGN16 Point {
PCL_ADD_POINT4D;
float intensity;
uint32_t t;
uint16_t reflectivity;
uint8_t ring;
uint16_t ambient;
uint32_t range;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
} // namespace ouster_ros
POINT_CLOUD_REGISTER_POINT_STRUCT(ouster_ros::Point,
(float, x, x)
(float, y, y)
(float, z, z)
(float, intensity, intensity)
// use std::uint32_t to avoid conflicting with pcl::uint32_t
(std::uint32_t, t, t)
(std::uint16_t, reflectivity, reflectivity)
(std::uint8_t, ring, ring)
(std::uint16_t, ambient, ambient)
(std::uint32_t, range, range)
)
// namespace pandar_ros
namespace pandar_ros {
struct EIGEN_ALIGN16 Point {
PCL_ADD_POINT4D;
float intensity;
double timestamp;
uint16_t ring;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
}
POINT_CLOUD_REGISTER_POINT_STRUCT(pandar_ros::Point,
(float, x, x)
(float, y, y)
(float, z, z)
(float, intensity, intensity)
(double, timestamp, timestamp)
(std::uint16_t, ring, ring)
)
//ANCHOR robosense modify
namespace robosense_ros {
struct EIGEN_ALIGN16 Point {
PCL_ADD_POINT4D;
std::uint8_t intensity;
std::uint16_t ring;
double timestamp;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
}
// namespace robosense_ros
POINT_CLOUD_REGISTER_POINT_STRUCT(robosense_ros::Point,
(float, x, x)
(float, y, y)
(float, z, z)
// use std::uint32_t to avoid conflicting with pcl::uint32_t
(std::uint8_t, intensity, intensity)
(std::uint16_t, ring, ring)
(double, timestamp, timestamp)

Most likely the datatype for the ring field is different (e.g. the bag as the ring as a uint8 instead of a uint16) in which case you can just make the change in these lines.

@Vor-Art
Copy link

Vor-Art commented May 17, 2024

I have simular warning:

Failed to find match for field 'reflectivity'. 
Failed to find match for field 'ring'. 
Failed to find match for field 'ambient'. 
Failed to find match for field 'range'.

These warnings occur due to the specifics of different lidar data.
You need to look at the data header and figure out which fields you have.

I handle this warning this way:

  1. Collect some of the lidar data

    rostopic echo /os1_points > test_lidar.txt
    
  2. Display header of one message:

    $ head test_lidar.txt -n42
    header: 
      seq: 5
      stamp: 
        secs: 1565943694
        nsecs: 928035526
      frame_id: "ouster"
    height: 1
    width: 65537
    fields: 
      - 
        name: "x"
        offset: 0
        datatype: 7
        count: 1
      - 
        name: "y"
        offset: 4
        datatype: 7
        count: 1
      - 
        name: "z"
        offset: 8
        datatype: 7
        count: 1
      - 
        name: "intensity"
        offset: 16
        datatype: 7
        count: 1
      - 
        name: "t"
        offset: 20
        datatype: 6
        count: 1
      - 
        name: "ring"
        offset: 24
        datatype: 5
        count: 1
    is_bigendian: False
    point_step: 32
    row_step: 2097184
    data: [.......]
    is_dense: True
    ---
    
  3. Update preprocess.h file:

    You can check the docks to choose the right fuild types: sensor_msgs/PointField and sensor_msgs/PointCloud2
    image

  4. Rebuild project: catkin build

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants