Skip to content

Crash in gps_input.cpp: can't subtract times with different time sources #2038

@schashni

Description

@schashni

Issue details:

  1. Launch mavros with the gps_input plugin enabled.
  2. Publish a message to /mavros/gps_input/gps_input
  3. crash in src/plugins/gps_input.cpp

The crash happens on this line:

if ((now_ - last_pos_time).to_chrono<std::chrono::nanoseconds>() < rate_period) {

last_pos_time is initialized to RCL_SYSTEM_TIME and now_ is initialized to RCL_ROS_TIME. They cannot be subtracted.

The issue looks completely similar to this: #1734

The workaround is the same (initializing last_pos_time to RCL_ROS_TIME):

rclcpp::Time last_pos_time{0, 0, RCL_ROS_TIME};

I'm happy to provide a small PR.

MAVROS version and platform

Mavros: ros2 HEAD (8cfe42e)
ROS: Humble
Ubuntu: 22.04
Autopilot type and version

[ x ] ArduPilot
[ ] PX4

Version: ArduSub V4.6.0-dev (0805156d)

Running ArduSub in SITL.

Node logs:

[ardusub-1] bind port 5762 for SERIAL1
[ardusub-1] SERIAL1 on TCP port 5762
[ardusub-1] bind port 5763 for SERIAL2
[ardusub-1] SERIAL2 on TCP port 5763
[ardusub-1] Loaded defaults from /home/anem/swarm-vehicle/ros2_ws/install/orca_bringup/share/orca_bringup/cfg/sub.parm
[ardusub-1] validate_structures:528: Validating structures
[ardusub-1] Loaded defaults from /home/anem/swarm-vehicle/ros2_ws/install/orca_bringup/share/orca_bringup/cfg/sub.parm
[ardusub-1] Loaded defaults from /home/anem/swarm-vehicle/ros2_ws/install/orca_bringup/share/orca_bringup/cfg/sub.parm
[ardusub-1] Loaded defaults from /home/anem/swarm-vehicle/ros2_ws/install/orca_bringup/share/orca_bringup/cfg/sub.parm
[mavros_node-7] [INFO] [1746950461.210246359] [mavros_router]: link[1000] detected remote address 1.1
[mavros_node-7] [WARN] [1746950461.211533274] [mavros.cmd]: CMD: Unexpected command 520, result 0
[mavros_node-7] [INFO] [1746950461.213142868] [mavros]: CON: Got HEARTBEAT, connected. FCU: ArduPilot
[mavros_node-7] [INFO] [1746950461.213918963] [mavros.sys]: VER: 1.1: Capabilities         0x000000000000f9e7
[mavros_node-7] [INFO] [1746950461.213960167] [mavros.sys]: VER: 1.1: Flight software:     04060000 (0805156d)
[mavros_node-7] [INFO] [1746950461.213984254] [mavros.sys]: VER: 1.1: Middleware software: 00000000 (        )
[mavros_node-7] [INFO] [1746950461.214042176] [mavros.sys]: VER: 1.1: OS software:         00000000 (        )
[mavros_node-7] [INFO] [1746950461.214060917] [mavros.sys]: VER: 1.1: Board hardware:      00000000
[mavros_node-7] [INFO] [1746950461.214075462] [mavros.sys]: VER: 1.1: VID/PID:             0000:0000
[mavros_node-7] [INFO] [1746950461.214086507] [mavros.sys]: VER: 1.1: UID:                 0000000000000000
[mavros_node-7] [INFO] [1746950461.333848856] [mavros.sys]: FCU: Calibrating barometer
[mavros_node-7] [INFO] [1746950462.980734528] [mavros.sys]: FCU: Barometer 1 calibration complete
[mavros_node-7] [INFO] [1746950462.980954788] [mavros.sys]: FCU: Barometer 2 calibration complete
[mavros_node-7] [INFO] [1746950462.987310976] [mavros.sys]: FCU: ArduPilot Ready
[mavros_node-7] [INFO] [1746950462.987793064] [mavros.sys]: FCU: AHRS: DCM active
[mavros_node-7] [INFO] [1746950463.004834135] [mavros.sys]: FCU: GPS 1: specified as MAV
[mavros_node-7] [INFO] [1746950463.303594318] [mavros.rc]: RC_CHANNELS message detected!
[mavros_node-7] [INFO] [1746950463.304204009] [mavros.imu]: IMU: Raw IMU message used.
[mavros_node-7] [INFO] [1746950465.173870766] [mavros.sys]: FCU: EKF3 IMU0 initialised
[mavros_node-7] [INFO] [1746950465.174720246] [mavros.sys]: FCU: EKF3 IMU1 initialised
[mavros_node-7] [INFO] [1746950465.177152288] [mavros.sys]: FCU: AHRS: EKF3 active
[mavros_node-7] [INFO] [1746950466.904022640] [mavros.sys]: FCU: EKF3 IMU0 tilt alignment complete
[mavros_node-7] [INFO] [1746950466.904365580] [mavros.sys]: FCU: EKF3 IMU1 tilt alignment complete
[mavros_node-7] [INFO] [1746950467.004056642] [mavros.sys]: FCU: EKF3 IMU0 MAG0 initial yaw alignment complete
[mavros_node-7] [INFO] [1746950467.004349695] [mavros.sys]: FCU: EKF3 IMU1 MAG0 initial yaw alignment complete
[mavros_node-7] terminate called after throwing an instance of 'std::runtime_error'
[mavros_node-7]   what():  can't subtract times with different time sources [1 != 2]
[ardusub-1] Closed connection on SERIAL0
[ERROR] [mavros_node-7]: process has died [pid 316356, exit code -6, cmd '/home/anem/swarm-vehicle/ros2_ws/install/mavros/lib/mavros/mavros_node --ros-args --params-file /home/anem/swarm-vehicle/ros2_ws/install/orca_bringup/share/orca_bringup/params/sim_mavros_params.yaml'].
``

Metadata

Metadata

Assignees

No one assigned

    Labels

    Type

    Projects

    No projects

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions