PX4 / PX4-Autopilot

PX4 Autopilot Software
https://px4.io
BSD 3-Clause "New" or "Revised" License
8.2k stars 13.37k forks source link

make file to do reply for ekf2 #20229

Open tahan094 opened 2 years ago

tahan094 commented 2 years ago

Describe the bug

Following the guide here https://docs.px4.io/main/en/debug/system_wide_replay.html, I get the issue when calling "make px4_sitl none" "[0/2] Re-checking globbed directories... ninja: error: unknown target 'none', did you mean 'tunes'? make: *** [Makefile:237: px4_sitl] Error 1"

To Reproduce

Steps to reproduce the behavior: use the guideline for replaying ekf2 after export the mode and the ulg file

Expected behavior

to have the replay working and to get "INFO [replay] Replay done (published 9917 msgs, 2.136 s)" also to have the following path created /PX4-Autopilot/build/px4_sitl_default_replay/tmp/rootfs/replay_params.txt

Log Files and Screenshots

NA, only using vs code and the guide u provided

Add screenshots to help explain your problem.

Drone (please complete the following information):

NA

Additional context

NA

dagar commented 2 years ago

This is a regression I'll fix shortly.

tahan094 commented 2 years ago

Thanks. Can you send me the fix after you do or tell me how to get it? Because I'm new 😊

tahan094 commented 2 years ago

@dagar do you have an estimate for this fix? I really need it asap

tahan094 commented 1 year ago

@dagar hello?!

tahan094 commented 1 year ago

@dagar I tried to checkout v1.12.3 and to do the replay but it seems that the structure was not the same between it an 1.13 as it gives error that time stamp could not be read??, and I really need to use 1.13 as it includes the NMEA and it is needed at my side for specific GPS that can not be changed. So, do you have an estimate?

tahan094 commented 1 year ago

@dagar hello, u have an estimate for the change please answer me?

tahan094 commented 1 year ago

@dagar hello why do you ignore me?

dagar commented 1 year ago

Please try https://github.com/PX4/PX4-Autopilot/pull/20282.

tahan094 commented 1 year ago

Hello, it is worked but has a lot issues as you can see below

Other issue related to pyulog make px4_sitl none [0/2] Re-checking globbed directories... [0/1] cd /home/tahan094/PX4-Autopilot/build/px4_sitl_default_replay/rootfs && /home/tahan094/PX4-Autopilot/build/px4_sitl_default_replay/bin/px4 INFO [uORB] Using orb rules from ./orb_publisher.rules


| \ \ \ / / / | | |/ / \ V / / /| | | / / \ / /_| | | | / /^\ \ __ | _| \/ \/ |/

px4 starting.

INFO [px4] startup script: /bin/sh etc/init.d-posix/rcS 0 SDLOG_DIRS_MAX: curr: 0 -> new: 7 SDLOG_PROFILE: curr: 1 -> new: 3 INFO [replay] using replay log file: /home/tahan094/Desktop/Fly5/log_7_٢٠٧٠-١-١-٠٢-٥٧-٢٦.ulg INFO [replay] Applying params from ULog file... INFO [replay] Applying override params from ./replay_params.txt... INFO [ekf2] replay mode enabled WARN [ekf2] Use EKF2_GPS_CTRL instead

INFO [logger] logger started (mode=all) INFO [logger] Start file log (type: full) INFO [logger] [logger] ./log/2022-09-23/11_30_05_replayed.ulg INFO [logger] Opened full log file: ./log/2022-09-23/11_30_05_replayed.ulg INFO [replay] Ekf2 replay mode INFO [replay] Applying params from ULog file... INFO [replay] Applying override params from ./replay_params.txt... INFO [replay] Replay in progress... ERROR [replay] Formats for actuator_armed don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - bool armed WARN [replay] - bool prearmed WARN [replay] - bool ready_to_arm WARN [replay] - bool lockdown WARN [replay] - bool manual_lockdown WARN [replay] - bool force_failsafe WARN [replay] - bool in_esc_calibration_mode ERROR [replay] - uint8_t[1] _padding0 WARN [replay] File format : uint64_t timestamp;bool armed;bool prearmed;bool ready_to_arm;bool lockdow WARN [replay] - uint64_t timestamp WARN [replay] - bool armed WARN [replay] - bool prearmed WARN [replay] - bool ready_to_arm WARN [replay] - bool lockdown WARN [replay] - bool manual_lockdown WARN [replay] - bool force_failsafe WARN [replay] - bool in_esc_calibration_mode ERROR [replay] - bool soft_stop ERROR [replay] Formats for actuator_controls_0 don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample ERROR [replay] - float[9] control ERROR [replay] - uint8_t[4] _padding0 WARN [replay] File format : uint64_t timestamp;uint64_t timestamp_sample;float[8] control; WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample ERROR [replay] - float[8] control WARN [replay] Topic actuator_controls_3 not found internally. Will ignore it ERROR [replay] Formats for failure_detector_status don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - float imbalanced_prop_metric ERROR [replay] - uint16_t motor_failure_mask WARN [replay] - bool fd_roll WARN [replay] - bool fd_pitch WARN [replay] - bool fd_alt WARN [replay] - bool fd_ext WARN [replay] - bool fd_arm_escs WARN [replay] - bool fd_battery WARN [replay] - bool fd_imbalanced_prop ERROR [replay] - bool fd_motor ERROR [replay] - uint8_t[2] _padding0 WARN [replay] File format : uint64_t timestamp;float imbalanced_prop_metric;bool fd_roll;bool fd_pitch WARN [replay] - uint64_t timestamp WARN [replay] - float imbalanced_prop_metric WARN [replay] - bool fd_roll WARN [replay] - bool fd_pitch WARN [replay] - bool fd_alt WARN [replay] - bool fd_ext WARN [replay] - bool fd_arm_escs ERROR [replay] - bool fd_high_wind WARN [replay] - bool fd_battery WARN [replay] - bool fd_imbalanced_prop ERROR [replay] - uint8_t[4] _padding0 INFO [px4] Startup script returned successfully pxh> ERROR [replay] Formats for manual_control_switches don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t switch_changes WARN [replay] - uint8_t mode_slot WARN [replay] - uint8_t arm_switch WARN [replay] - uint8_t return_switch WARN [replay] - uint8_t loiter_switch WARN [replay] - uint8_t offboard_switch WARN [replay] - uint8_t kill_switch WARN [replay] - uint8_t gear_switch WARN [replay] - uint8_t transition_switch WARN [replay] - uint8_t photo_switch WARN [replay] - uint8_t video_switch ERROR [replay] - uint8_t engage_main_motor_switch ERROR [replay] - uint8_t[1] _padding0 WARN [replay] File format : uint64_t timestamp;uint64_t timestamp_sample;uint32_t switch_changes;uint8 WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t switch_changes WARN [replay] - uint8_t mode_slot WARN [replay] - uint8_t arm_switch WARN [replay] - uint8_t return_switch WARN [replay] - uint8_t loiter_switch WARN [replay] - uint8_t offboard_switch WARN [replay] - uint8_t kill_switch WARN [replay] - uint8_t gear_switch WARN [replay] - uint8_t transition_switch WARN [replay] - uint8_t photo_switch WARN [replay] - uint8_t video_switch ERROR [replay] - uint8_t[2] _padding0 ERROR [replay] Formats for px4io_status don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - float voltage_v WARN [replay] - float rssi_v WARN [replay] - uint16_t free_memory_bytes WARN [replay] - uint16_t[8] pwm WARN [replay] - uint16_t[8] pwm_disarmed WARN [replay] - uint16_t[8] pwm_failsafe WARN [replay] - uint16_t[8] pwm_rate_hz WARN [replay] - uint16_t[18] raw_inputs WARN [replay] - bool status_arm_sync WARN [replay] - bool status_failsafe WARN [replay] - bool status_fmu_initialized WARN [replay] - bool status_fmu_ok WARN [replay] - bool status_init_ok WARN [replay] - bool status_outputs_armed WARN [replay] - bool status_raw_pwm WARN [replay] - bool status_rc_ok WARN [replay] - bool status_rc_dsm WARN [replay] - bool status_rc_ppm WARN [replay] - bool status_rc_sbus WARN [replay] - bool status_rc_st24 WARN [replay] - bool status_rc_sumd ERROR [replay] - bool status_safety_button_event WARN [replay] - bool alarm_pwm_error WARN [replay] - bool alarm_rc_lost WARN [replay] - bool arming_failsafe_custom WARN [replay] - bool arming_fmu_armed WARN [replay] - bool arming_fmu_prearmed WARN [replay] - bool arming_force_failsafe WARN [replay] - bool arming_io_arm_ok WARN [replay] - bool arming_lockdown WARN [replay] - bool arming_termination_failsafe WARN [replay] - uint8_t[3] _padding0 WARN [replay] File format : uint64_t timestamp;float voltage_v;float rssi_v;uint16_t free_memory_bytes WARN [replay] - uint64_t timestamp WARN [replay] - float voltage_v WARN [replay] - float rssi_v WARN [replay] - uint16_t free_memory_bytes WARN [replay] - uint16_t[8] pwm WARN [replay] - uint16_t[8] pwm_disarmed WARN [replay] - uint16_t[8] pwm_failsafe WARN [replay] - uint16_t[8] pwm_rate_hz WARN [replay] - uint16_t[18] raw_inputs WARN [replay] - bool status_arm_sync WARN [replay] - bool status_failsafe WARN [replay] - bool status_fmu_initialized WARN [replay] - bool status_fmu_ok WARN [replay] - bool status_init_ok WARN [replay] - bool status_outputs_armed WARN [replay] - bool status_raw_pwm WARN [replay] - bool status_rc_ok WARN [replay] - bool status_rc_dsm WARN [replay] - bool status_rc_ppm WARN [replay] - bool status_rc_sbus WARN [replay] - bool status_rc_st24 WARN [replay] - bool status_rc_sumd ERROR [replay] - bool status_safety_off WARN [replay] - bool alarm_pwm_error WARN [replay] - bool alarm_rc_lost WARN [replay] - bool arming_failsafe_custom WARN [replay] - bool arming_fmu_armed WARN [replay] - bool arming_fmu_prearmed WARN [replay] - bool arming_force_failsafe WARN [replay] - bool arming_io_arm_ok WARN [replay] - bool arming_lockdown WARN [replay] - bool arming_termination_failsafe WARN [replay] - uint8_t[3] _padding0 WARN [replay] Topic safety not found internally. Will ignore it ERROR [replay] Formats for sensor_combined don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - float[3] gyro_rad WARN [replay] - uint32_t gyro_integral_dt WARN [replay] - int32_t accelerometer_timestamp_relative WARN [replay] - float[3] accelerometer_m_s2 WARN [replay] - uint32_t accelerometer_integral_dt WARN [replay] - uint8_t accelerometer_clipping ERROR [replay] - uint8_t gyro_clipping WARN [replay] - uint8_t accel_calibration_count WARN [replay] - uint8_t gyro_calibration_count WARN [replay] File format : uint64_t timestamp;float[3] gyro_rad;uint32_t gyro_integral_dt;int32_t acc WARN [replay] - uint64_t timestamp WARN [replay] - float[3] gyro_rad WARN [replay] - uint32_t gyro_integral_dt WARN [replay] - int32_t accelerometer_timestamp_relative WARN [replay] - float[3] accelerometer_m_s2 WARN [replay] - uint32_t accelerometer_integral_dt WARN [replay] - uint8_t accelerometer_clipping WARN [replay] - uint8_t accel_calibration_count WARN [replay] - uint8_t gyro_calibration_count ERROR [replay] - uint8_t[1] _padding0 ERROR [replay] Formats for vehicle_attitude_setpoint don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - float roll_body WARN [replay] - float pitch_body WARN [replay] - float yaw_body WARN [replay] - float yaw_sp_move_rate WARN [replay] - float[4] q_d WARN [replay] - float[3] thrust_body ERROR [replay] - bool reset_rate_integrals WARN [replay] - bool fw_control_yaw WARN [replay] - uint8_t apply_flaps ERROR [replay] - uint8_t apply_spoilers WARN [replay] File format : uint64_t timestamp;float roll_body;float pitch_body;float yaw_body;float y WARN [replay] - uint64_t timestamp WARN [replay] - float roll_body WARN [replay] - float pitch_body WARN [replay] - float yaw_body WARN [replay] - float yaw_sp_move_rate WARN [replay] - float[4] q_d WARN [replay] - float[3] thrust_body ERROR [replay] - bool roll_reset_integral ERROR [replay] - bool pitch_reset_integral ERROR [replay] - bool yaw_reset_integral WARN [replay] - bool fw_control_yaw WARN [replay] - uint8_t apply_flaps ERROR [replay] - uint8_t[7] _padding0 ERROR [replay] Formats for vehicle_gps_position don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp ERROR [replay] - uint64_t timestamp_sample WARN [replay] - uint64_t time_utc_usec ERROR [replay] - uint32_t device_id WARN [replay] - int32_t lat WARN [replay] - int32_t lon WARN [replay] - int32_t alt WARN [replay] - int32_t alt_ellipsoid WARN [replay] - float s_variance_m_s WARN [replay] - float c_variance_rad WARN [replay] - float eph WARN [replay] - float epv WARN [replay] - float hdop WARN [replay] - float vdop WARN [replay] - int32_t noise_per_ms WARN [replay] - int32_t jamming_indicator WARN [replay] - float vel_m_s WARN [replay] - float vel_n_m_s WARN [replay] - float vel_e_m_s WARN [replay] - float vel_d_m_s WARN [replay] - float cog_rad WARN [replay] - int32_t timestamp_time_relative WARN [replay] - float heading WARN [replay] - float heading_offset ERROR [replay] - float heading_accuracy ERROR [replay] - float rtcm_injection_rate ERROR [replay] - uint16_t automatic_gain_control WARN [replay] - uint8_t fix_type WARN [replay] - uint8_t jamming_state WARN [replay] - bool vel_ned_valid WARN [replay] - uint8_t satellites_used ERROR [replay] - uint8_t selected_rtcm_instance ERROR [replay] - uint8_t[5] _padding0 WARN [replay] File format : uint64_t timestamp;uint64_t time_utc_usec;int32_t lat;int32_t lon;int32_t WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t time_utc_usec WARN [replay] - int32_t lat WARN [replay] - int32_t lon WARN [replay] - int32_t alt WARN [replay] - int32_t alt_ellipsoid WARN [replay] - float s_variance_m_s WARN [replay] - float c_variance_rad WARN [replay] - float eph WARN [replay] - float epv WARN [replay] - float hdop WARN [replay] - float vdop WARN [replay] - int32_t noise_per_ms WARN [replay] - int32_t jamming_indicator WARN [replay] - float vel_m_s WARN [replay] - float vel_n_m_s WARN [replay] - float vel_e_m_s WARN [replay] - float vel_d_m_s WARN [replay] - float cog_rad WARN [replay] - int32_t timestamp_time_relative WARN [replay] - float heading WARN [replay] - float heading_offset WARN [replay] - uint8_t fix_type WARN [replay] - uint8_t jamming_state WARN [replay] - bool vel_ned_valid WARN [replay] - uint8_t satellites_used WARN [replay] - uint8_t selected ERROR [replay] - uint8_t[3] _padding0 ERROR [replay] Formats for vehicle_local_position don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint64_t ref_timestamp WARN [replay] - double ref_lat WARN [replay] - double ref_lon WARN [replay] - float x WARN [replay] - float y WARN [replay] - float z WARN [replay] - float[2] delta_xy WARN [replay] - float delta_z WARN [replay] - float vx WARN [replay] - float vy WARN [replay] - float vz WARN [replay] - float z_deriv WARN [replay] - float[2] delta_vxy WARN [replay] - float delta_vz WARN [replay] - float ax WARN [replay] - float ay WARN [replay] - float az WARN [replay] - float heading WARN [replay] - float delta_heading WARN [replay] - float ref_alt WARN [replay] - float dist_bottom WARN [replay] - float eph WARN [replay] - float epv WARN [replay] - float evh WARN [replay] - float evv WARN [replay] - float vxy_max WARN [replay] - float vz_max WARN [replay] - float hagl_min WARN [replay] - float hagl_max WARN [replay] - bool xy_valid WARN [replay] - bool z_valid WARN [replay] - bool v_xy_valid WARN [replay] - bool v_z_valid WARN [replay] - uint8_t xy_reset_counter WARN [replay] - uint8_t z_reset_counter WARN [replay] - uint8_t vxy_reset_counter WARN [replay] - uint8_t vz_reset_counter WARN [replay] - uint8_t heading_reset_counter WARN [replay] - bool heading_good_for_control WARN [replay] - bool xy_global WARN [replay] - bool z_global WARN [replay] - bool dist_bottom_valid WARN [replay] - uint8_t dist_bottom_sensor_bitfield ERROR [replay] - bool dead_reckoning ERROR [replay] - uint8_t[1] _padding0 WARN [replay] File format : uint64_t timestamp;uint64_t timestamp_sample;uint64_t ref_timestamp;double WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint64_t ref_timestamp WARN [replay] - double ref_lat WARN [replay] - double ref_lon WARN [replay] - float x WARN [replay] - float y WARN [replay] - float z WARN [replay] - float[2] delta_xy WARN [replay] - float delta_z WARN [replay] - float vx WARN [replay] - float vy WARN [replay] - float vz WARN [replay] - float z_deriv WARN [replay] - float[2] delta_vxy WARN [replay] - float delta_vz WARN [replay] - float ax WARN [replay] - float ay WARN [replay] - float az WARN [replay] - float heading WARN [replay] - float delta_heading WARN [replay] - float ref_alt WARN [replay] - float dist_bottom WARN [replay] - float eph WARN [replay] - float epv WARN [replay] - float evh WARN [replay] - float evv WARN [replay] - float vxy_max WARN [replay] - float vz_max WARN [replay] - float hagl_min WARN [replay] - float hagl_max WARN [replay] - bool xy_valid WARN [replay] - bool z_valid WARN [replay] - bool v_xy_valid WARN [replay] - bool v_z_valid WARN [replay] - uint8_t xy_reset_counter WARN [replay] - uint8_t z_reset_counter WARN [replay] - uint8_t vxy_reset_counter WARN [replay] - uint8_t vz_reset_counter WARN [replay] - uint8_t heading_reset_counter WARN [replay] - bool heading_good_for_control WARN [replay] - bool xy_global WARN [replay] - bool z_global WARN [replay] - bool dist_bottom_valid WARN [replay] - uint8_t dist_bottom_sensor_bitfield ERROR [replay] - uint8_t[2] _padding0 ERROR [replay] Formats for vehicle_status don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t armed_time WARN [replay] - uint64_t takeoff_time WARN [replay] - uint64_t nav_state_timestamp WARN [replay] - uint64_t failsafe_timestamp ERROR [replay] - uint16_t failure_detector_status WARN [replay] - uint8_t arming_state WARN [replay] - uint8_t latest_arming_reason WARN [replay] - uint8_t latest_disarming_reason WARN [replay] - uint8_t nav_state WARN [replay] - uint8_t hil_state WARN [replay] - uint8_t vehicle_type WARN [replay] - bool failsafe WARN [replay] - bool rc_signal_lost WARN [replay] - bool data_link_lost WARN [replay] - uint8_t data_link_lost_counter WARN [replay] - bool high_latency_data_link_lost WARN [replay] - bool is_vtol WARN [replay] - bool is_vtol_tailsitter WARN [replay] - bool in_transition_mode WARN [replay] - bool in_transition_to_fw WARN [replay] - bool mission_failure WARN [replay] - bool geofence_violated WARN [replay] - uint8_t system_type WARN [replay] - uint8_t system_id WARN [replay] - uint8_t component_id ERROR [replay] - bool safety_button_available ERROR [replay] - bool safety_off ERROR [replay] - bool auto_mission_available ERROR [replay] - bool power_input_valid ERROR [replay] - bool usb_connected ERROR [replay] - bool parachute_system_present ERROR [replay] - bool parachute_system_healthy ERROR [replay] - bool avoidance_system_required ERROR [replay] - bool avoidance_system_valid WARN [replay] - uint8_t[1] _padding0 WARN [replay] File format : uint64_t timestamp;uint64_t nav_state_timestamp;uint64_t failsafe_timestam WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t nav_state_timestamp WARN [replay] - uint64_t failsafe_timestamp ERROR [replay] - uint64_t onboard_control_sensors_present ERROR [replay] - uint64_t onboard_control_sensors_enabled ERROR [replay] - uint64_t onboard_control_sensors_health WARN [replay] - uint64_t armed_time WARN [replay] - uint64_t takeoff_time WARN [replay] - uint8_t nav_state WARN [replay] - uint8_t arming_state WARN [replay] - uint8_t hil_state WARN [replay] - bool failsafe WARN [replay] - uint8_t system_type WARN [replay] - uint8_t system_id WARN [replay] - uint8_t component_id WARN [replay] - uint8_t vehicle_type WARN [replay] - bool is_vtol WARN [replay] - bool is_vtol_tailsitter ERROR [replay] - bool vtol_fw_permanent_stab WARN [replay] - bool in_transition_mode WARN [replay] - bool in_transition_to_fw WARN [replay] - bool rc_signal_lost WARN [replay] - bool data_link_lost WARN [replay] - uint8_t data_link_lost_counter WARN [replay] - bool high_latency_data_link_lost ERROR [replay] - bool engine_failure WARN [replay] - bool mission_failure WARN [replay] - bool geofence_violated ERROR [replay] - uint8_t failure_detector_status WARN [replay] - uint8_t latest_arming_reason WARN [replay] - uint8_t latest_disarming_reason WARN [replay] - uint8_t[1] _padding0 ERROR [replay] Formats for vehicle_status_flags don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp ERROR [replay] - uint32_t mode_req_angular_velocity ERROR [replay] - uint32_t mode_req_attitude ERROR [replay] - uint32_t mode_req_local_position ERROR [replay] - uint32_t mode_req_local_position_relaxed ERROR [replay] - uint32_t mode_req_global_position ERROR [replay] - uint32_t mode_req_local_alt ERROR [replay] - uint32_t mode_req_mission ERROR [replay] - uint32_t mode_req_offboard_signal ERROR [replay] - uint32_t mode_req_home_position ERROR [replay] - uint32_t mode_req_prevent_arming ERROR [replay] - uint32_t mode_req_other WARN [replay] - bool calibration_enabled ERROR [replay] - bool pre_flight_checks_pass WARN [replay] - bool auto_mission_available WARN [replay] - bool angular_velocity_valid WARN [replay] - bool attitude_valid WARN [replay] - bool local_altitude_valid WARN [replay] - bool local_position_valid ERROR [replay] - bool local_position_valid_relaxed WARN [replay] - bool local_velocity_valid WARN [replay] - bool global_position_valid WARN [replay] - bool gps_position_valid WARN [replay] - bool home_position_valid WARN [replay] - bool offboard_control_signal_lost WARN [replay] - bool rc_signal_found_once WARN [replay] - bool rc_calibration_in_progress WARN [replay] - bool vtol_transition_failure ERROR [replay] - bool battery_low_remaining_time ERROR [replay] - bool battery_unhealthy ERROR [replay] - uint8_t battery_warning WARN [replay] - uint8_t[1] _padding0 WARN [replay] File format : uint64_t timestamp;bool calibration_enabled;bool system_sensors_initialize WARN [replay] - uint64_t timestamp WARN [replay] - bool calibration_enabled ERROR [replay] - bool system_sensors_initialized ERROR [replay] - bool system_hotplug_timeout WARN [replay] - bool auto_mission_available WARN [replay] - bool angular_velocity_valid WARN [replay] - bool attitude_valid WARN [replay] - bool local_altitude_valid WARN [replay] - bool local_position_valid WARN [replay] - bool local_velocity_valid WARN [replay] - bool global_position_valid WARN [replay] - bool gps_position_valid WARN [replay] - bool home_position_valid ERROR [replay] - bool power_input_valid ERROR [replay] - bool battery_healthy ERROR [replay] - bool escs_error ERROR [replay] - bool escs_failure ERROR [replay] - bool position_reliant_on_gps ERROR [replay] - bool position_reliant_on_optical_flow ERROR [replay] - bool position_reliant_on_vision_position ERROR [replay] - bool dead_reckoning ERROR [replay] - bool flight_terminated ERROR [replay] - bool circuit_breaker_engaged_power_check ERROR [replay] - bool circuit_breaker_engaged_airspd_check ERROR [replay] - bool circuit_breaker_engaged_enginefailure_check ERROR [replay] - bool circuit_breaker_flight_termination_disabled ERROR [replay] - bool circuit_breaker_engaged_usb_check ERROR [replay] - bool circuit_breaker_engaged_posfailure_check ERROR [replay] - bool circuit_breaker_vtol_fw_arming_check WARN [replay] - bool offboard_control_signal_lost WARN [replay] - bool rc_signal_found_once WARN [replay] - bool rc_calibration_in_progress ERROR [replay] - bool rc_calibration_valid WARN [replay] - bool vtol_transition_failure ERROR [replay] - bool usb_connected ERROR [replay] - bool sd_card_detected_once ERROR [replay] - bool avoidance_system_required ERROR [replay] - bool avoidance_system_valid ERROR [replay] - bool parachute_system_present ERROR [replay] - bool parachute_system_healthy WARN [replay] - uint8_t[1] _padding0 ERROR [replay] Formats for control_allocator_status don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - float[3] allocated_torque WARN [replay] - float[3] unallocated_torque WARN [replay] - float[3] allocated_thrust WARN [replay] - float[3] unallocated_thrust ERROR [replay] - uint16_t handled_motor_failure_mask WARN [replay] - bool torque_setpoint_achieved WARN [replay] - bool thrust_setpoint_achieved WARN [replay] - int8_t[16] actuator_saturation ERROR [replay] - uint8_t[4] _padding0 WARN [replay] File format : uint64_t timestamp;float[3] allocated_torque;float[3] unallocated_torque;f WARN [replay] - uint64_t timestamp WARN [replay] - float[3] allocated_torque WARN [replay] - float[3] unallocated_torque WARN [replay] - float[3] allocated_thrust WARN [replay] - float[3] unallocated_thrust WARN [replay] - bool torque_setpoint_achieved WARN [replay] - bool thrust_setpoint_achieved WARN [replay] - int8_t[16] actuator_saturation ERROR [replay] - uint8_t[6] _padding0 ERROR [replay] Formats for control_allocator_status don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - float[3] allocated_torque WARN [replay] - float[3] unallocated_torque WARN [replay] - float[3] allocated_thrust WARN [replay] - float[3] unallocated_thrust ERROR [replay] - uint16_t handled_motor_failure_mask WARN [replay] - bool torque_setpoint_achieved WARN [replay] - bool thrust_setpoint_achieved WARN [replay] - int8_t[16] actuator_saturation ERROR [replay] - uint8_t[4] _padding0 WARN [replay] File format : uint64_t timestamp;float[3] allocated_torque;float[3] unallocated_torque;f WARN [replay] - uint64_t timestamp WARN [replay] - float[3] allocated_torque WARN [replay] - float[3] unallocated_torque WARN [replay] - float[3] allocated_thrust WARN [replay] - float[3] unallocated_thrust WARN [replay] - bool torque_setpoint_achieved WARN [replay] - bool thrust_setpoint_achieved WARN [replay] - int8_t[16] actuator_saturation ERROR [replay] - uint8_t[6] _padding0 ERROR [replay] Formats for rate_ctrl_status don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - float rollspeed_integ WARN [replay] - float pitchspeed_integ WARN [replay] - float yawspeed_integ ERROR [replay] - float wheel_rate_integ WARN [replay] File format : uint64_t timestamp;float rollspeed_integ;float pitchspeed_integ;float yaws WARN [replay] - uint64_t timestamp WARN [replay] - float rollspeed_integ WARN [replay] - float pitchspeed_integ WARN [replay] - float yawspeed_integ ERROR [replay] - float additional_integ1 ERROR [replay] Formats for estimator_event_flags don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t information_event_changes WARN [replay] - uint32_t warning_event_changes WARN [replay] - bool gps_checks_passed WARN [replay] - bool reset_vel_to_gps WARN [replay] - bool reset_vel_to_flow WARN [replay] - bool reset_vel_to_vision WARN [replay] - bool reset_vel_to_zero WARN [replay] - bool reset_pos_to_last_known WARN [replay] - bool reset_pos_to_gps WARN [replay] - bool reset_pos_to_vision WARN [replay] - bool starting_gps_fusion WARN [replay] - bool starting_vision_pos_fusion WARN [replay] - bool starting_vision_vel_fusion WARN [replay] - bool starting_vision_yaw_fusion WARN [replay] - bool yaw_aligned_to_imu_gps ERROR [replay] - bool reset_hgt_to_baro ERROR [replay] - bool reset_hgt_to_gps ERROR [replay] - bool reset_hgt_to_rng ERROR [replay] - bool reset_hgt_to_ev WARN [replay] - bool gps_quality_poor WARN [replay] - bool gps_fusion_timout WARN [replay] - bool gps_data_stopped WARN [replay] - bool gps_data_stopped_using_alternate WARN [replay] - bool height_sensor_timeout WARN [replay] - bool stopping_navigation WARN [replay] - bool invalid_accel_bias_cov_reset WARN [replay] - bool bad_yaw_using_gps_course WARN [replay] - bool stopping_mag_use WARN [replay] - bool vision_data_stopped WARN [replay] - bool emergency_yaw_reset_mag_stopped WARN [replay] - bool emergency_yaw_reset_gps_yaw_stopped ERROR [replay] - uint8_t[3] _padding0 WARN [replay] File format : uint64_t timestamp;uint64_t timestamp_sample;uint32_t information_event_ch WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t information_event_changes WARN [replay] - uint32_t warning_event_changes WARN [replay] - bool gps_checks_passed WARN [replay] - bool reset_vel_to_gps WARN [replay] - bool reset_vel_to_flow WARN [replay] - bool reset_vel_to_vision WARN [replay] - bool reset_vel_to_zero WARN [replay] - bool reset_pos_to_last_known WARN [replay] - bool reset_pos_to_gps WARN [replay] - bool reset_pos_to_vision WARN [replay] - bool starting_gps_fusion WARN [replay] - bool starting_vision_pos_fusion WARN [replay] - bool starting_vision_vel_fusion WARN [replay] - bool starting_vision_yaw_fusion WARN [replay] - bool yaw_aligned_to_imu_gps WARN [replay] - bool gps_quality_poor WARN [replay] - bool gps_fusion_timout WARN [replay] - bool gps_data_stopped WARN [replay] - bool gps_data_stopped_using_alternate WARN [replay] - bool height_sensor_timeout WARN [replay] - bool stopping_navigation WARN [replay] - bool invalid_accel_bias_cov_reset WARN [replay] - bool bad_yaw_using_gps_course WARN [replay] - bool stopping_mag_use WARN [replay] - bool vision_data_stopped WARN [replay] - bool emergency_yaw_reset_mag_stopped WARN [replay] - bool emergency_yaw_reset_gps_yaw_stopped ERROR [replay] - uint8_t[7] _padding0 ERROR [replay] Formats for estimator_status don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample ERROR [replay] - uint64_t control_mode_flags WARN [replay] - float[3] output_tracking_error WARN [replay] - uint32_t filter_fault_flags WARN [replay] - float pos_horiz_accuracy WARN [replay] - float pos_vert_accuracy WARN [replay] - float mag_test_ratio WARN [replay] - float vel_test_ratio WARN [replay] - float pos_test_ratio WARN [replay] - float hgt_test_ratio WARN [replay] - float tas_test_ratio WARN [replay] - float hagl_test_ratio WARN [replay] - float beta_test_ratio WARN [replay] - float time_slip WARN [replay] - uint32_t accel_device_id WARN [replay] - uint32_t gyro_device_id WARN [replay] - uint32_t baro_device_id WARN [replay] - uint32_t mag_device_id WARN [replay] - uint16_t gps_check_fail_flags WARN [replay] - uint16_t innovation_check_flags WARN [replay] - uint16_t solution_status_flags WARN [replay] - uint8_t reset_count_vel_ne WARN [replay] - uint8_t reset_count_vel_d WARN [replay] - uint8_t reset_count_pos_ne WARN [replay] - uint8_t reset_count_pod_d WARN [replay] - uint8_t reset_count_quat WARN [replay] - bool pre_flt_fail_innov_heading WARN [replay] - bool pre_flt_fail_innov_vel_horiz WARN [replay] - bool pre_flt_fail_innov_vel_vert WARN [replay] - bool pre_flt_fail_innov_height WARN [replay] - bool pre_flt_fail_mag_field_disturbed WARN [replay] - uint8_t health_flags WARN [replay] - uint8_t timeout_flags ERROR [replay] - uint8_t[6] _padding0 WARN [replay] File format : uint64_t timestamp;uint64_t timestamp_sample;float[3] output_tracking_erro WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - float[3] output_tracking_error ERROR [replay] - uint32_t control_mode_flags WARN [replay] - uint32_t filter_fault_flags WARN [replay] - float pos_horiz_accuracy WARN [replay] - float pos_vert_accuracy WARN [replay] - float mag_test_ratio WARN [replay] - float vel_test_ratio WARN [replay] - float pos_test_ratio WARN [replay] - float hgt_test_ratio WARN [replay] - float tas_test_ratio WARN [replay] - float hagl_test_ratio WARN [replay] - float beta_test_ratio WARN [replay] - float time_slip WARN [replay] - uint32_t accel_device_id WARN [replay] - uint32_t gyro_device_id WARN [replay] - uint32_t baro_device_id WARN [replay] - uint32_t mag_device_id WARN [replay] - uint16_t gps_check_fail_flags WARN [replay] - uint16_t innovation_check_flags WARN [replay] - uint16_t solution_status_flags WARN [replay] - uint8_t reset_count_vel_ne WARN [replay] - uint8_t reset_count_vel_d WARN [replay] - uint8_t reset_count_pos_ne WARN [replay] - uint8_t reset_count_pod_d WARN [replay] - uint8_t reset_count_quat WARN [replay] - bool pre_flt_fail_innov_heading WARN [replay] - bool pre_flt_fail_innov_vel_horiz WARN [replay] - bool pre_flt_fail_innov_vel_vert WARN [replay] - bool pre_flt_fail_innov_height WARN [replay] - bool pre_flt_fail_mag_field_disturbed WARN [replay] - uint8_t health_flags WARN [replay] - uint8_t timeout_flags ERROR [replay] - uint8_t[2] _padding0 ERROR [replay] Formats for estimator_status_flags don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t control_status_changes WARN [replay] - uint32_t fault_status_changes WARN [replay] - uint32_t innovation_fault_status_changes WARN [replay] - bool cs_tilt_align WARN [replay] - bool cs_yaw_align WARN [replay] - bool cs_gps WARN [replay] - bool cs_opt_flow WARN [replay] - bool cs_mag_hdg WARN [replay] - bool cs_mag_3d WARN [replay] - bool cs_mag_dec WARN [replay] - bool cs_in_air WARN [replay] - bool cs_wind WARN [replay] - bool cs_baro_hgt WARN [replay] - bool cs_rng_hgt WARN [replay] - bool cs_gps_hgt WARN [replay] - bool cs_ev_pos WARN [replay] - bool cs_ev_yaw WARN [replay] - bool cs_ev_hgt WARN [replay] - bool cs_fuse_beta WARN [replay] - bool cs_mag_field_disturbed WARN [replay] - bool cs_fixed_wing WARN [replay] - bool cs_mag_fault WARN [replay] - bool cs_fuse_aspd WARN [replay] - bool cs_gnd_effect WARN [replay] - bool cs_rng_stuck WARN [replay] - bool cs_gps_yaw WARN [replay] - bool cs_mag_aligned_in_flight WARN [replay] - bool cs_ev_vel WARN [replay] - bool cs_synthetic_mag_z WARN [replay] - bool cs_vehicle_at_rest WARN [replay] - bool cs_gps_yaw_fault WARN [replay] - bool cs_rng_fault WARN [replay] - bool cs_inertial_dead_reckoning WARN [replay] - bool cs_wind_dead_reckoning WARN [replay] - bool cs_rng_kin_consistent ERROR [replay] - bool cs_fake_pos ERROR [replay] - bool cs_fake_hgt WARN [replay] - bool fs_bad_mag_x WARN [replay] - bool fs_bad_mag_y WARN [replay] - bool fs_bad_mag_z WARN [replay] - bool fs_bad_hdg WARN [replay] - bool fs_bad_mag_decl WARN [replay] - bool fs_bad_airspeed WARN [replay] - bool fs_bad_sideslip WARN [replay] - bool fs_bad_optflow_x WARN [replay] - bool fs_bad_optflow_y WARN [replay] - bool fs_bad_vel_n WARN [replay] - bool fs_bad_vel_e WARN [replay] - bool fs_bad_vel_d WARN [replay] - bool fs_bad_pos_n WARN [replay] - bool fs_bad_pos_e WARN [replay] - bool fs_bad_pos_d WARN [replay] - bool fs_bad_acc_bias WARN [replay] - bool fs_bad_acc_vertical WARN [replay] - bool fs_bad_acc_clipping WARN [replay] - bool reject_hor_vel WARN [replay] - bool reject_ver_vel WARN [replay] - bool reject_hor_pos WARN [replay] - bool reject_ver_pos WARN [replay] - bool reject_yaw WARN [replay] - bool reject_airspeed WARN [replay] - bool reject_sideslip WARN [replay] - bool reject_hagl WARN [replay] - bool reject_optflow_x WARN [replay] - bool reject_optflow_y ERROR [replay] - uint8_t[6] _padding0 WARN [replay] File format : uint64_t timestamp;uint64_t timestamp_sample;uint32_t control_status_chang WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t control_status_changes WARN [replay] - uint32_t fault_status_changes WARN [replay] - uint32_t innovation_fault_status_changes WARN [replay] - bool cs_tilt_align WARN [replay] - bool cs_yaw_align WARN [replay] - bool cs_gps WARN [replay] - bool cs_opt_flow WARN [replay] - bool cs_mag_hdg WARN [replay] - bool cs_mag_3d WARN [replay] - bool cs_mag_dec WARN [replay] - bool cs_in_air WARN [replay] - bool cs_wind WARN [replay] - bool cs_baro_hgt WARN [replay] - bool cs_rng_hgt WARN [replay] - bool cs_gps_hgt WARN [replay] - bool cs_ev_pos WARN [replay] - bool cs_ev_yaw WARN [replay] - bool cs_ev_hgt WARN [replay] - bool cs_fuse_beta WARN [replay] - bool cs_mag_field_disturbed WARN [replay] - bool cs_fixed_wing WARN [replay] - bool cs_mag_fault WARN [replay] - bool cs_fuse_aspd WARN [replay] - bool cs_gnd_effect WARN [replay] - bool cs_rng_stuck WARN [replay] - bool cs_gps_yaw WARN [replay] - bool cs_mag_aligned_in_flight WARN [replay] - bool cs_ev_vel WARN [replay] - bool cs_synthetic_mag_z WARN [replay] - bool cs_vehicle_at_rest WARN [replay] - bool cs_gps_yaw_fault WARN [replay] - bool cs_rng_fault WARN [replay] - bool cs_inertial_dead_reckoning WARN [replay] - bool cs_wind_dead_reckoning WARN [replay] - bool cs_rng_kin_consistent WARN [replay] - bool fs_bad_mag_x WARN [replay] - bool fs_bad_mag_y WARN [replay] - bool fs_bad_mag_z WARN [replay] - bool fs_bad_hdg WARN [replay] - bool fs_bad_mag_decl WARN [replay] - bool fs_bad_airspeed WARN [replay] - bool fs_bad_sideslip WARN [replay] - bool fs_bad_optflow_x WARN [replay] - bool fs_bad_optflow_y WARN [replay] - bool fs_bad_vel_n WARN [replay] - bool fs_bad_vel_e WARN [replay] - bool fs_bad_vel_d WARN [replay] - bool fs_bad_pos_n WARN [replay] - bool fs_bad_pos_e WARN [replay] - bool fs_bad_pos_d WARN [replay] - bool fs_bad_acc_bias WARN [replay] - bool fs_bad_acc_vertical WARN [replay] - bool fs_bad_acc_clipping WARN [replay] - bool reject_hor_vel WARN [replay] - bool reject_ver_vel WARN [replay] - bool reject_hor_pos WARN [replay] - bool reject_ver_pos ERROR [replay] - bool reject_mag_x ERROR [replay] - bool reject_mag_y ERROR [replay] - bool reject_mag_z WARN [replay] - bool reject_yaw WARN [replay] - bool reject_airspeed WARN [replay] - bool reject_sideslip WARN [replay] - bool reject_hagl WARN [replay] - bool reject_optflow_x WARN [replay] - bool reject_optflow_y ERROR [replay] - uint8_t[5] _padding0 ERROR [replay] Formats for sensor_gps don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp ERROR [replay] - uint64_t timestamp_sample WARN [replay] - uint64_t time_utc_usec WARN [replay] - uint32_t device_id WARN [replay] - int32_t lat WARN [replay] - int32_t lon WARN [replay] - int32_t alt WARN [replay] - int32_t alt_ellipsoid WARN [replay] - float s_variance_m_s WARN [replay] - float c_variance_rad WARN [replay] - float eph WARN [replay] - float epv WARN [replay] - float hdop WARN [replay] - float vdop WARN [replay] - int32_t noise_per_ms WARN [replay] - int32_t jamming_indicator WARN [replay] - float vel_m_s WARN [replay] - float vel_n_m_s WARN [replay] - float vel_e_m_s WARN [replay] - float vel_d_m_s WARN [replay] - float cog_rad WARN [replay] - int32_t timestamp_time_relative WARN [replay] - float heading WARN [replay] - float heading_offset WARN [replay] - float heading_accuracy ERROR [replay] - float rtcm_injection_rate WARN [replay] - uint16_t automatic_gain_control WARN [replay] - uint8_t fix_type WARN [replay] - uint8_t jamming_state WARN [replay] - bool vel_ned_valid WARN [replay] - uint8_t satellites_used ERROR [replay] - uint8_t selected_rtcm_instance ERROR [replay] - uint8_t[5] _padding0 WARN [replay] File format : uint64_t timestamp;uint64_t time_utc_usec;uint32_t device_id;int32_t lat;i WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t time_utc_usec WARN [replay] - uint32_t device_id WARN [replay] - int32_t lat WARN [replay] - int32_t lon WARN [replay] - int32_t alt WARN [replay] - int32_t alt_ellipsoid WARN [replay] - float s_variance_m_s WARN [replay] - float c_variance_rad WARN [replay] - float eph WARN [replay] - float epv WARN [replay] - float hdop WARN [replay] - float vdop WARN [replay] - int32_t noise_per_ms WARN [replay] - int32_t jamming_indicator WARN [replay] - float vel_m_s WARN [replay] - float vel_n_m_s WARN [replay] - float vel_e_m_s WARN [replay] - float vel_d_m_s WARN [replay] - float cog_rad WARN [replay] - int32_t timestamp_time_relative WARN [replay] - float heading WARN [replay] - float heading_offset WARN [replay] - float heading_accuracy WARN [replay] - uint16_t automatic_gain_control WARN [replay] - uint8_t fix_type WARN [replay] - uint8_t jamming_state WARN [replay] - bool vel_ned_valid WARN [replay] - uint8_t satellites_used ERROR [replay] - uint8_t[2] _padding0 ERROR [replay] Formats for sensor_gyro don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t device_id WARN [replay] - float x WARN [replay] - float y WARN [replay] - float z WARN [replay] - float temperature WARN [replay] - uint32_t error_count ERROR [replay] - uint8_t[3] clip_counter WARN [replay] - uint8_t samples ERROR [replay] - uint8_t[4] _padding0 WARN [replay] File format : uint64_t timestamp;uint64_t timestamp_sample;uint32_t device_id;float x;fl WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t device_id WARN [replay] - float x WARN [replay] - float y WARN [replay] - float z WARN [replay] - float temperature WARN [replay] - uint32_t error_count WARN [replay] - uint8_t samples ERROR [replay] - uint8_t[7] _padding0 ERROR [replay] Formats for sensor_gyro don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t device_id WARN [replay] - float x WARN [replay] - float y WARN [replay] - float z WARN [replay] - float temperature WARN [replay] - uint32_t error_count ERROR [replay] - uint8_t[3] clip_counter WARN [replay] - uint8_t samples ERROR [replay] - uint8_t[4] _padding0 WARN [replay] File format : uint64_t timestamp;uint64_t timestamp_sample;uint32_t device_id;float x;fl WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t device_id WARN [replay] - float x WARN [replay] - float y WARN [replay] - float z WARN [replay] - float temperature WARN [replay] - uint32_t error_count WARN [replay] - uint8_t samples ERROR [replay] - uint8_t[7] _padding0 ERROR [replay] Formats for vehicle_imu don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t accel_device_id WARN [replay] - uint32_t gyro_device_id WARN [replay] - float[3] delta_angle WARN [replay] - float[3] delta_velocity WARN [replay] - uint16_t delta_angle_dt WARN [replay] - uint16_t delta_velocity_dt ERROR [replay] - uint8_t delta_angle_clipping WARN [replay] - uint8_t delta_velocity_clipping WARN [replay] - uint8_t accel_calibration_count WARN [replay] - uint8_t gyro_calibration_count WARN [replay] File format : uint64_t timestamp;uint64_t timestamp_sample;uint32_t accel_device_id;uint WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t accel_device_id WARN [replay] - uint32_t gyro_device_id WARN [replay] - float[3] delta_angle WARN [replay] - float[3] delta_velocity WARN [replay] - uint16_t delta_angle_dt WARN [replay] - uint16_t delta_velocity_dt WARN [replay] - uint8_t delta_velocity_clipping WARN [replay] - uint8_t accel_calibration_count WARN [replay] - uint8_t gyro_calibration_count ERROR [replay] - uint8_t[1] _padding0 ERROR [replay] Formats for vehicle_imu don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t accel_device_id WARN [replay] - uint32_t gyro_device_id WARN [replay] - float[3] delta_angle WARN [replay] - float[3] delta_velocity WARN [replay] - uint16_t delta_angle_dt WARN [replay] - uint16_t delta_velocity_dt ERROR [replay] - uint8_t delta_angle_clipping WARN [replay] - uint8_t delta_velocity_clipping WARN [replay] - uint8_t accel_calibration_count WARN [replay] - uint8_t gyro_calibration_count WARN [replay] File format : uint64_t timestamp;uint64_t timestamp_sample;uint32_t accel_device_id;uint WARN [replay] - uint64_t timestamp WARN [replay] - uint64_t timestamp_sample WARN [replay] - uint32_t accel_device_id WARN [replay] - uint32_t gyro_device_id WARN [replay] - float[3] delta_angle WARN [replay] - float[3] delta_velocity WARN [replay] - uint16_t delta_angle_dt WARN [replay] - uint16_t delta_velocity_dt WARN [replay] - uint8_t delta_velocity_clipping WARN [replay] - uint8_t accel_calibration_count WARN [replay] - uint8_t gyro_calibration_count ERROR [replay] - uint8_t[1] _padding0 ERROR [replay] Formats for vehicle_imu_status don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint32_t accel_device_id WARN [replay] - uint32_t gyro_device_id WARN [replay] - uint32_t[3] accel_clipping ERROR [replay] - uint32_t[3] gyro_clipping WARN [replay] - uint32_t accel_error_count WARN [replay] - uint32_t gyro_error_count WARN [replay] - float accel_rate_hz WARN [replay] - float gyro_rate_hz WARN [replay] - float accel_raw_rate_hz WARN [replay] - float gyro_raw_rate_hz WARN [replay] - float accel_vibration_metric WARN [replay] - float gyro_vibration_metric WARN [replay] - float delta_angle_coning_metric WARN [replay] - float[3] mean_accel WARN [replay] - float[3] mean_gyro WARN [replay] - float[3] var_accel WARN [replay] - float[3] var_gyro WARN [replay] - float temperature_accel WARN [replay] - float temperature_gyro ERROR [replay] - uint8_t[4] _padding0 WARN [replay] File format : uint64_t timestamp;uint32_t accel_device_id;uint32_t gyro_device_id;uint32 WARN [replay] - uint64_t timestamp WARN [replay] - uint32_t accel_device_id WARN [replay] - uint32_t gyro_device_id WARN [replay] - uint32_t[3] accel_clipping WARN [replay] - uint32_t accel_error_count WARN [replay] - uint32_t gyro_error_count WARN [replay] - float accel_rate_hz WARN [replay] - float gyro_rate_hz WARN [replay] - float accel_raw_rate_hz WARN [replay] - float gyro_raw_rate_hz WARN [replay] - float accel_vibration_metric WARN [replay] - float gyro_vibration_metric WARN [replay] - float delta_angle_coning_metric WARN [replay] - float[3] mean_accel WARN [replay] - float[3] mean_gyro WARN [replay] - float[3] var_accel WARN [replay] - float[3] var_gyro WARN [replay] - float temperature_accel WARN [replay] - float temperature_gyro ERROR [replay] Formats for vehicle_imu_status don't match. Will ignore it. WARN [replay] Internal format: WARN [replay] - uint64_t timestamp WARN [replay] - uint32_t accel_device_id WARN [replay] - uint32_t gyro_device_id WARN [replay] - uint32_t[3] accel_clipping ERROR [replay] - uint32_t[3] gyro_clipping WARN [replay] - uint32_t accel_error_count WARN [replay] - uint32_t gyro_error_count WARN [replay] - float accel_rate_hz WARN [replay] - float gyro_rate_hz WARN [replay] - float accel_raw_rate_hz WARN [replay] - float gyro_raw_rate_hz WARN [replay] - float accel_vibration_metric WARN [replay] - float gyro_vibration_metric WARN [replay] - float delta_angle_coning_metric WARN [replay] - float[3] mean_accel WARN [replay] - float[3] mean_gyro WARN [replay] - float[3] var_accel WARN [ekf2] Use EKF2_GPS_CTRL instead

WARN [replay] - float[3] var_gyro WARN [replay] - float temperature_accel WARN [replay] - float temperature_gyro ERROR [replay] - uint8_t[4] _padding0 WARN [replay] File format : uint64_t timestamp;uint32_t accel_device_id;uint32_t gyro_device_id;uint32 WARN [replay] - uint64_t timestamp WARN [replay] - uint32_t accel_device_id WARN [replay] - uint32_t gyro_device_id WARN [replay] - uint32_t[3] accel_clipping WARN [replay] - uint32_t accel_error_count WARN [replay] - uint32_t gyro_error_count WARN [replay] - float accel_rate_hz WARN [replay] - float gyro_rate_hz WARN [replay] - float accel_raw_rate_hz WARN [replay] - float gyro_raw_rate_hz WARN [replay] - float accel_vibration_metric WARN [replay] - float gyro_vibration_metric WARN [replay] - float delta_angle_coning_metric WARN [replay] - float[3] mean_accel WARN [replay] - float[3] mean_gyro WARN [replay] - float[3] var_accel WARN [replay] - float[3] var_gyro WARN [replay] - float temperature_accel WARN [replay] - float temperature_gyro ERROR [replay] Dropout in replayed log, 2 ms ERROR [replay] Dropout in replayed log, 201 ms ERROR [replay] Dropout in replayed log, 217 ms ERROR [replay] Dropout in replayed log, 13 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 230 ms ERROR [replay] Dropout in replayed log, 192 ms ERROR [replay] Dropout in replayed log, 70 ms ERROR [replay] Dropout in replayed log, 126 ms ERROR [replay] Dropout in replayed log, 248 ms ERROR [replay] Dropout in replayed log, 251 ms ERROR [replay] Dropout in replayed log, 116 ms ERROR [replay] Dropout in replayed log, 62 ms ERROR [replay] Dropout in replayed log, 216 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 38 ms ERROR [replay] Dropout in replayed log, 158 ms ERROR [replay] Dropout in replayed log, 10 ms ERROR [replay] Dropout in replayed log, 199 ms ERROR [replay] Dropout in replayed log, 10 ms ERROR [replay] Dropout in replayed log, 259 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 311 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 192 ms ERROR [replay] Dropout in replayed log, 223 ms ERROR [replay] Dropout in replayed log, 91 ms ERROR [replay] Dropout in replayed log, 220 ms ERROR [replay] Dropout in replayed log, 233 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 188 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 195 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 234 ms ERROR [replay] Dropout in replayed log, 147 ms ERROR [replay] Dropout in replayed log, 69 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 185 ms ERROR [replay] Dropout in replayed log, 17 ms ERROR [replay] Dropout in replayed log, 185 ms ERROR [replay] Dropout in replayed log, 101 ms ERROR [replay] Dropout in replayed log, 94 ms ERROR [replay] Dropout in replayed log, 228 ms ERROR [replay] Dropout in replayed log, 287 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 181 ms ERROR [replay] Dropout in replayed log, 288 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 238 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 221 ms ERROR [replay] Dropout in replayed log, 3 ms ERROR [replay] Dropout in replayed log, 202 ms ERROR [replay] Dropout in replayed log, 206 ms ERROR [replay] Dropout in replayed log, 182 ms ERROR [replay] Dropout in replayed log, 17 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 188 ms ERROR [replay] Dropout in replayed log, 3 ms ERROR [replay] Dropout in replayed log, 120 ms ERROR [replay] Dropout in replayed log, 129 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 293 ms ERROR [replay] Dropout in replayed log, 3 ms ERROR [replay] Dropout in replayed log, 192 ms ERROR [replay] Dropout in replayed log, 234 ms ERROR [replay] Dropout in replayed log, 0 ms ERROR [replay] Dropout in replayed log, 93 ms ERROR [replay] Dropout in replayed log, 160 ms INFO [replay] Replay done (published 31 msgs, 0.773 s) INFO [replay] INFO [replay] Topic, Num Published, Num Error (no timestamp match found): INFO [replay] vehicle_air_data: 409, 2 INFO [replay] vehicle_magnetometer: 275, 2 INFO [logger] closed logfile, bytes written: 111105 Powering off NOW.Exiting NOW.

tahan094 commented 1 year ago

Pyulog issue tahan094@tahan094:~/PX4-Autopilot$ ulog_params -i "$replay" -d ' ' | grep -e '^EKF2' > build/px4_sitl_default_replay/rootfs/replay_params.txt Traceback (most recent call last): File "/home/tahan094/.local/bin/ulog_params", line 8, in sys.exit(main()) File "/home/tahan094/.local/lib/python3.8/site-packages/pyulog/params.py", line 62, in main params = get_defaults(ulog, args.default) File "/home/tahan094/.local/lib/python3.8/site-packages/pyulog/params.py", line 20, in get_defaults raise Exception('invalid value \'{}\' for --default'.format(default)) Exception: invalid value ' ' for --default

dagar commented 1 year ago

You need to replay with the exact same version of PX4 (or at least the .msg files must match).

tahan094 commented 1 year ago

Can you please clarify what to write in the command, I am using px4 fmu v3 Normally I used these commands as described here

export replay_mode=ekf2 export replay= make px4_sitl none

tahan094 commented 1 year ago

Hello @dagar I will open this as an issue