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

GPS/GNSS Synchronization DELAY #228

Open
HaroldMurcia opened this issue Oct 12, 2023 · 0 comments
Open

GPS/GNSS Synchronization DELAY #228

HaroldMurcia opened this issue Oct 12, 2023 · 0 comments
Labels
question Further information is requested

Comments

@HaroldMurcia
Copy link

HaroldMurcia commented Oct 12, 2023

Describe your question
Hello,
In the current configuration with my LiDAR I want to synchronise several sensors. The LiDAR is taking the timestamp directly from the GPS/GNSS with the PPS and serial-NMEA lines. Then I use rosbag record /ouster/metadata /ouster/imu_packets /ouster/lidar_packets and process the generated bag file with ouster/replay.launch in my computer.

image

On the computer a chrony service synchronises the clock with the same GNSS clock using gpsd with a second serial connection. When I determine the time difference (online) between the ouster received messages and the ROS time, there is a time difference of < 0.05 secs. approximately:

ros::Subscriber ouster_sub = nh.subscribe("/ouster/points", 10, &MyROSNode::ousterCallback, this);
void ousterCallback(const sensor_msgs::PointCloud2ConstPtr& pointcloud_msg) {
        int64_t last_lidar_timestamp_ = pointcloud_msg->header.stamp.toNSec();
        int64_t last_lidar_ros_timestamp_ = ros::Time::now().toNSec();
        int64_t LiDAR_rostime_timestamp = last_lidar_timestamp_ - last_lidar_ros_timestamp_;
        . . .

However, when evaluating the rosbag imu/linear_acceleration and imu/twist responses from the /ouster/imu rostopic with respect to other sensors in my system (rostime based), I notice a time difference around -0.27 secs

  1. Any idea how to correct or reduce this time difference ?
  2. Is PTP a better option, considering that my on-board GPS is SERIAL connection? (The example configuration is for an ethernet GPS grandmaster clock.

Screenshots
/ouster/imu/twist/z = red signal
image
/ouster/imu/linear acceleration = green signal
image

Platform:

  • Ouster Sensor= OS1-128 REV 7
  • Ouster Firmware Version=v3.0.1
  • Programming Language= C++, ROS1 Noetic
  • Operating System= Linux Ubuntu 20.04
  • Machine Architecture= x64

Catkin makefile:

all : debug release

debug:
        catkin_make --cmake-args -DCMAKE_BUILD_TYPE=Debug

release:
        catkin_make --cmake-args -DCMAKE_BUILD_TYPE=Release -DCATKIN_WHITELIST_PACKAGES="ouster_ros"

Roslauch:

<include file="$(find ouster_ros)/launch/sensor.launch"> 
            <arg name="sensor_hostname" value="os-122313000337.local"/> 
            <arg name="udp_profile_lidar" value="RNG19_RFL8_SIG16_NIR16_DUAL"/> 
            <arg name="lidar_mode" value="2048x10"/> 
           <arg name="timestamp_mode" value="TIME_FROM_SYNC_PULSE_IN" /> 
            <arg name="viz" value="false"/>
            <arg name="tf_prefix" value=""/>
 </include>

get_sensor_info {"prod_line": "OS-1-128", "prod_pn": "860-105010-07", "prod_sn": "122313000337", "image_rev": "ousteros-image-prod-bootes-v3.0.1+20230209044733", "build_rev": "v3.0.1", "build_date": "2023-02-09T04:49:03Z", "status": "RUNNING", "initialization_id": 1629346}

get_time_info {"timestamp": {"time": 1696851520.9933181, "mode": "TIME_FROM_SYNC_PULSE_IN", "time_options": {"ptp_1588": 1651175671, "sync_pulse_in": 1696851520, "internal_osc": 7923}}, "sync_pulse_in": {"locked": 1, "polarity": "ACTIVE_LOW", "diagnostics": {"last_period_nsec": 0, "count": 7923, "count_unfiltered": 7056}}, "multipurpose_io": {"mode": "INPUT_NMEA_UART", "sync_pulse_out": {"polarity": "ACTIVE_HIGH", "frequency_hz": 1, "angle_deg": 360, "pulse_width_ms": 10}, "nmea": {"locked": 1, "polarity": "ACTIVE_LOW", "ignore_valid_char": 0, "baud_rate": "BAUD_9600", "leap_seconds": 0, "diagnostics": {"decoding": {"utc_decoded_count": 6291, "date_decoded_count": 6010, "not_valid_count": 281, "last_read_message": "GPRMC,113840.00,A,4333.7201301,N,00128.6298792,E,0.255,230.1,091023,0.0,E,D*37"}, "io_checks": {"start_char_count": 6742, "char_count": 508001, "bit_count": 1469122, "bit_count_unfiltered": 1469121}}}}}

@HaroldMurcia HaroldMurcia added the question Further information is requested label Oct 12, 2023
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
question Further information is requested
Projects
None yet
Development

No branches or pull requests

1 participant