mavlink / mavros

MAVLink to ROS gateway with proxy for Ground Control Station
Other
889 stars 991 forks source link

fake_gps not affecting global_position, making offboard control impossible #1665

Open michaelb-sm opened 2 years ago

michaelb-sm commented 2 years ago

Issue details

I am attempting to fly indoor in a GPS denied environment, and so am trying to use fake_gps to allow me to enter offboard mode. Currently I do not have a mocap/vision system available so I am publishing a static pose estimate to the /mavros/fake_gps/mocap/pose topic from a custom node. However even with this node running in the background, I don't see any data being published to /mavros/global_position/global or /mavros/hil/gps, and thus am unable to either set my home position or enter offboard mode.

I am using a Pixhawk 4 Mini with Jetson Nano 2GB as a companion computer, and QGroundControl to configure the Mini. I have MAV_USEHILGPS set to 1 in QGroundControl and am receiving data on GPS_RAW_INT in Mavlink Inspector, so I know that the Mini is receiving data of some kind. Connection to the Mini is established over the Jetson's GPIO pins, and I launch mavros with the following:

roslaunch mavros px4.launch fcu_url:=/dev/ttyTHS1:921600

fake_gps plugin in px4_config.yaml

# fake_gps
fake_gps:
  # select data source
  use_mocap: true         # ~mocap/pose
  mocap_transform: false   # ~mocap/tf instead of pose
  use_vision: false       # ~vision (pose)
  use_hil_gps: true
  # origin (default: Zürich)
  geo_origin:
    lat: 43.663360          # latitude [degrees]
    lon: -79.393587           # longitude [degrees]
    alt: 97.336            # altitude (height over the WGS-84 ellipsoid) [meters]
  eph: 2.0
  epv: 2.0
  satellites_visible: 5   # virtual number of visible satellites
  fix_type: 3             # type of GPS fix (default: 3D)
  tf:
    listen: false
    send: false           # send TF?
    frame_id: "map"       # TF frame_id
    child_frame_id: "fix" # TF child_frame_id
    rate_limit: 10.0      # TF rate
  gps_rate: 5.0           # GPS data publishing rate

Readout from GPS_RAW_INT in MAVlink Inspector

This data does differ from that specified in the plugin config, not sure why/how that would change, but it only appears when I publish to fake_gps image

Published message to /mavros/fake_gps/mocap/pose

header: 
  seq: 46
  stamp: 
    secs: 1638391613
    nsecs: 321658931
  frame_id: "map"
pose: 
  position: 
    x: 0.0
    y: 0.0
    z: 0.0
  orientation: 
    x: 0.0
    y: 0.0
    z: 0.0
    w: 1.0

MAVROS version and platform

Mavros: ?0.18.4? ROS: Melodic Ubuntu: 18.04

Autopilot type and version

[ ] ArduPilot [ X ] PX4

Version: ?3.7.1?

Node logs

CLEAR PARAMETERS
 * /mavros/

PARAMETERS
 * /mavros/cmd/use_comp_id_system_control: False
 * /mavros/conn/heartbeat_rate: 1.0
 * /mavros/conn/system_time_rate: 1.0
 * /mavros/conn/timeout: 10.0
 * /mavros/conn/timesync_rate: 10.0
 * /mavros/distance_sensor/hrlv_ez4_pub/field_of_view: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/frame_id: hrlv_ez4_sonar
 * /mavros/distance_sensor/hrlv_ez4_pub/id: 0
 * /mavros/distance_sensor/hrlv_ez4_pub/orientation: PITCH_270
 * /mavros/distance_sensor/hrlv_ez4_pub/send_tf: True
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/laser_1_sub/id: 3
 * /mavros/distance_sensor/laser_1_sub/orientation: PITCH_270
 * /mavros/distance_sensor/laser_1_sub/subscriber: True
 * /mavros/distance_sensor/lidarlite_pub/field_of_view: 0.0
 * /mavros/distance_sensor/lidarlite_pub/frame_id: lidarlite_laser
 * /mavros/distance_sensor/lidarlite_pub/id: 1
 * /mavros/distance_sensor/lidarlite_pub/orientation: PITCH_270
 * /mavros/distance_sensor/lidarlite_pub/send_tf: True
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/sonar_1_sub/horizontal_fov_ratio: 1.0
 * /mavros/distance_sensor/sonar_1_sub/id: 2
 * /mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270
 * /mavros/distance_sensor/sonar_1_sub/subscriber: True
 * /mavros/distance_sensor/sonar_1_sub/vertical_fov_ratio: 1.0
 * /mavros/fake_gps/eph: 2.0
 * /mavros/fake_gps/epv: 2.0
 * /mavros/fake_gps/fix_type: 3
 * /mavros/fake_gps/geo_origin/alt: 97.336
 * /mavros/fake_gps/geo_origin/lat: 43.66336
 * /mavros/fake_gps/geo_origin/lon: -79.393587
 * /mavros/fake_gps/gps_rate: 5.0
 * /mavros/fake_gps/mocap_transform: False
 * /mavros/fake_gps/satellites_visible: 5
 * /mavros/fake_gps/tf/child_frame_id: fix
 * /mavros/fake_gps/tf/frame_id: map
 * /mavros/fake_gps/tf/listen: False
 * /mavros/fake_gps/tf/rate_limit: 10.0
 * /mavros/fake_gps/tf/send: False
 * /mavros/fake_gps/use_hil_gps: True
 * /mavros/fake_gps/use_mocap: True
 * /mavros/fake_gps/use_vision: False
 * /mavros/fcu_protocol: v2.0
 * /mavros/fcu_url: /dev/ttyTHS1:921600
 * /mavros/gcs_url: 
 * /mavros/global_position/child_frame_id: base_link
 * /mavros/global_position/frame_id: map
 * /mavros/global_position/gps_uere: 1.0
 * /mavros/global_position/rot_covariance: 99999.0
 * /mavros/global_position/tf/child_frame_id: base_link
 * /mavros/global_position/tf/frame_id: map
 * /mavros/global_position/tf/global_frame_id: earth
 * /mavros/global_position/tf/send: False
 * /mavros/global_position/use_relative_alt: True
 * /mavros/image/frame_id: px4flow
 * /mavros/imu/angular_velocity_stdev: 0.0003490659 // 0...
 * /mavros/imu/frame_id: base_link
 * /mavros/imu/linear_acceleration_stdev: 0.0003
 * /mavros/imu/magnetic_stdev: 0.0
 * /mavros/imu/orientation_stdev: 1.0
 * /mavros/landing_target/camera/fov_x: 2.0071286398
 * /mavros/landing_target/camera/fov_y: 2.0071286398
 * /mavros/landing_target/image/height: 480
 * /mavros/landing_target/image/width: 640
 * /mavros/landing_target/land_target_type: VISION_FIDUCIAL
 * /mavros/landing_target/listen_lt: False
 * /mavros/landing_target/mav_frame: LOCAL_NED
 * /mavros/landing_target/target_size/x: 0.3
 * /mavros/landing_target/target_size/y: 0.3
 * /mavros/landing_target/tf/child_frame_id: camera_center
 * /mavros/landing_target/tf/frame_id: landing_target
 * /mavros/landing_target/tf/listen: False
 * /mavros/landing_target/tf/rate_limit: 10.0
 * /mavros/landing_target/tf/send: True
 * /mavros/local_position/frame_id: map
 * /mavros/local_position/tf/child_frame_id: base_link
 * /mavros/local_position/tf/frame_id: map
 * /mavros/local_position/tf/send: False
 * /mavros/local_position/tf/send_fcu: False
 * /mavros/mission/pull_after_gcs: True
 * /mavros/mission/use_mission_item_int: True
 * /mavros/mocap/use_pose: True
 * /mavros/mocap/use_tf: False
 * /mavros/odometry/fcu/odom_child_id_des: base_link
 * /mavros/odometry/fcu/odom_parent_id_des: map
 * /mavros/plugin_blacklist: ['safety_area', '...
 * /mavros/plugin_whitelist: []
 * /mavros/px4flow/frame_id: px4flow
 * /mavros/px4flow/ranger_fov: 0.118682
 * /mavros/px4flow/ranger_max_range: 5.0
 * /mavros/px4flow/ranger_min_range: 0.3
 * /mavros/safety_area/p1/x: 1.0
 * /mavros/safety_area/p1/y: 1.0
 * /mavros/safety_area/p1/z: 1.0
 * /mavros/safety_area/p2/x: -1.0
 * /mavros/safety_area/p2/y: -1.0
 * /mavros/safety_area/p2/z: -1.0
 * /mavros/setpoint_accel/send_force: False
 * /mavros/setpoint_attitude/reverse_thrust: False
 * /mavros/setpoint_attitude/tf/child_frame_id: target_attitude
 * /mavros/setpoint_attitude/tf/frame_id: map
 * /mavros/setpoint_attitude/tf/listen: False
 * /mavros/setpoint_attitude/tf/rate_limit: 50.0
 * /mavros/setpoint_attitude/use_quaternion: False
 * /mavros/setpoint_position/mav_frame: LOCAL_NED
 * /mavros/setpoint_position/tf/child_frame_id: target_position
 * /mavros/setpoint_position/tf/frame_id: map
 * /mavros/setpoint_position/tf/listen: False
 * /mavros/setpoint_position/tf/rate_limit: 50.0
 * /mavros/setpoint_raw/thrust_scaling: 1.0
 * /mavros/setpoint_velocity/mav_frame: LOCAL_NED
 * /mavros/startup_px4_usb_quirk: True
 * /mavros/sys/disable_diag: False
 * /mavros/sys/min_voltage: 10.0
 * /mavros/target_component_id: 1
 * /mavros/target_system_id: 1
 * /mavros/tdr_radio/low_rssi: 40
 * /mavros/time/time_ref_source: fcu
 * /mavros/time/timesync_avg_alpha: 0.6
 * /mavros/time/timesync_mode: MAVLINK
 * /mavros/vibration/frame_id: base_link
 * /mavros/vision_pose/tf/child_frame_id: vision_estimate
 * /mavros/vision_pose/tf/frame_id: odom
 * /mavros/vision_pose/tf/listen: False
 * /mavros/vision_pose/tf/rate_limit: 10.0
 * /mavros/vision_speed/listen_twist: True
 * /mavros/vision_speed/twist_cov: True
 * /mavros/wheel_odometry/child_frame_id: base_link
 * /mavros/wheel_odometry/count: 2
 * /mavros/wheel_odometry/frame_id: odom
 * /mavros/wheel_odometry/send_raw: True
 * /mavros/wheel_odometry/send_twist: False
 * /mavros/wheel_odometry/tf/child_frame_id: base_link
 * /mavros/wheel_odometry/tf/frame_id: odom
 * /mavros/wheel_odometry/tf/send: False
 * /mavros/wheel_odometry/use_rpm: False
 * /mavros/wheel_odometry/vel_error: 0.1
 * /mavros/wheel_odometry/wheel0/radius: 0.05
 * /mavros/wheel_odometry/wheel0/x: 0.0
 * /mavros/wheel_odometry/wheel0/y: -0.15
 * /mavros/wheel_odometry/wheel1/radius: 0.05
 * /mavros/wheel_odometry/wheel1/x: 0.0
 * /mavros/wheel_odometry/wheel1/y: 0.15
 * /rosdistro: melodic
 * /rosversion: 1.14.12

NODES
  /
    mavros (mavros/mavros_node)

auto-starting new master
process[master]: started with pid [30214]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 5283bf38-52f1-11ec-8eef-48b02d2e1bd5
process[rosout-1]: started with pid [30228]
started core service [/rosout]
process[mavros-2]: started with pid [30232]
[ INFO] [1638395701.739190021]: FCU URL: /dev/ttyTHS1:921600
[ INFO] [1638395701.749633233]: serial0: device: /dev/ttyTHS1 @ 921600 bps
[ INFO] [1638395701.751047484]: GCS bridge disabled
[ INFO] [1638395702.020788653]: Plugin 3dr_radio loaded
[ INFO] [1638395702.034140474]: Plugin 3dr_radio initialized
[ INFO] [1638395702.034533556]: Plugin actuator_control loaded
[ INFO] [1638395702.049677554]: Plugin actuator_control initialized
[ INFO] [1638395702.300961367]: Plugin adsb loaded
[ INFO] [1638395702.321894458]: Plugin adsb initialized
[ INFO] [1638395702.322435251]: Plugin altitude loaded
[ INFO] [1638395702.327631049]: Plugin altitude initialized
[ INFO] [1638395702.328173197]: Plugin cam_imu_sync loaded
[ INFO] [1638395702.331769271]: Plugin cam_imu_sync initialized
[ INFO] [1638395702.332364649]: Plugin command loaded
[ INFO] [1638395702.369215975]: Plugin command initialized
[ INFO] [1638395702.369679579]: Plugin companion_process_status loaded
[ INFO] [1638395702.380473580]: Plugin companion_process_status initialized
[ INFO] [1638395702.381127554]: Plugin debug_value loaded
[ INFO] [1638395702.403987252]: Plugin debug_value initialized
[ INFO] [1638395702.404445023]: Plugin distance_sensor loaded
[ INFO] [1638395702.506550835]: Plugin distance_sensor initialized
[ INFO] [1638395702.507281633]: Plugin esc_status loaded
[ INFO] [1638395702.514002623]: Plugin esc_status initialized
[ INFO] [1638395702.514601283]: Plugin esc_telemetry loaded
[ INFO] [1638395702.518870236]: Plugin esc_telemetry initialized
[ INFO] [1638395702.519754684]: Plugin fake_gps loaded
[ INFO] [1638395702.600196815]: Plugin fake_gps initialized
[ INFO] [1638395702.601040012]: Plugin ftp loaded
[ INFO] [1638395702.639296839]: Plugin ftp initialized
[ INFO] [1638395702.639942583]: Plugin geofence loaded
[ INFO] [1638395702.654163018]: Plugin geofence initialized
[ INFO] [1638395702.654690426]: Plugin global_position loaded
[ INFO] [1638395702.723260666]: Plugin global_position initialized
[ INFO] [1638395702.723795419]: Plugin gps_input loaded
[ INFO] [1638395702.737626469]: Plugin gps_input initialized
[ INFO] [1638395702.738167940]: Plugin gps_rtk loaded
[ INFO] [1638395702.751630285]: Plugin gps_rtk initialized
[ INFO] [1638395702.752068211]: Plugin gps_status loaded
[ INFO] [1638395702.762704813]: Plugin gps_status initialized
[ INFO] [1638395702.763334776]: Plugin hil loaded
[ INFO] [1638395702.821701914]: Plugin hil initialized
[ INFO] [1638395702.822302241]: Plugin home_position loaded
[ INFO] [1638395702.839328262]: Plugin home_position initialized
[ INFO] [1638395702.840183073]: Plugin imu loaded
[ INFO] [1638395702.873545568]: Plugin imu initialized
[ INFO] [1638395702.874077038]: Plugin landing_target loaded
[ INFO] [1638395702.931304984]: Plugin landing_target initialized
[ INFO] [1638395702.931812444]: Plugin local_position loaded
[ INFO] [1638395702.959089276]: Plugin local_position initialized
[ INFO] [1638395702.959598038]: Plugin log_transfer loaded
[ INFO] [1638395702.975209651]: Plugin log_transfer initialized
[ INFO] [1638395702.975667786]: Plugin mag_calibration_status loaded
[ INFO] [1638395702.980972233]: Plugin mag_calibration_status initialized
[ INFO] [1638395702.981499276]: Plugin manual_control loaded
[ INFO] [1638395702.997177141]: Plugin manual_control initialized
[ INFO] [1638395702.997937523]: Plugin mocap_pose_estimate loaded
[ INFO] [1638395703.013535854]: Plugin mocap_pose_estimate initialized
[ INFO] [1638395703.014012168]: Plugin mount_control loaded
[ INFO] [1638395703.032655309]: Plugin mount_control initialized
[ INFO] [1638395703.033167769]: Plugin nav_controller_output loaded
[ INFO] [1638395703.035801633]: Plugin nav_controller_output initialized
[ INFO] [1638395703.036206330]: Plugin obstacle_distance loaded
[ INFO] [1638395703.047291275]: Plugin obstacle_distance initialized
[ INFO] [1638395703.047800453]: Plugin odom loaded
[ INFO] [1638395703.067872222]: Plugin odom initialized
[ INFO] [1638395703.068298743]: Plugin onboard_computer_status loaded
[ INFO] [1638395703.077608438]: Plugin onboard_computer_status initialized
[ INFO] [1638395703.078200692]: Plugin param loaded
[ INFO] [1638395703.091885854]: Plugin param initialized
[ INFO] [1638395703.092349979]: Plugin play_tune loaded
[ INFO] [1638395703.102666885]: Plugin play_tune initialized
[ INFO] [1638395703.103124500]: Plugin px4flow loaded
[ INFO] [1638395703.131141298]: Plugin px4flow initialized
[ INFO] [1638395703.131652455]: Plugin rallypoint loaded
[ INFO] [1638395703.143155379]: Plugin rallypoint initialized
[ INFO] [1638395703.143670443]: Plugin rangefinder loaded
[ INFO] [1638395703.146476758]: Plugin rangefinder initialized
[ INFO] [1638395703.147185681]: Plugin rc_io loaded
[ INFO] [1638395703.162661614]: Plugin rc_io initialized
[ INFO] [1638395703.162810940]: Plugin safety_area blacklisted
[ INFO] [1638395703.163362464]: Plugin setpoint_accel loaded
[ INFO] [1638395703.175408160]: Plugin setpoint_accel initialized
[ INFO] [1638395703.176147396]: Plugin setpoint_attitude loaded
[ INFO] [1638395703.217843835]: Plugin setpoint_attitude initialized
[ INFO] [1638395703.218390202]: Plugin setpoint_position loaded
[ INFO] [1638395703.280890978]: Plugin setpoint_position initialized
[ INFO] [1638395703.281392656]: Plugin setpoint_raw loaded
[ INFO] [1638395703.321048683]: Plugin setpoint_raw initialized
[ INFO] [1638395703.321555413]: Plugin setpoint_trajectory loaded
[ INFO] [1638395703.343843692]: Plugin setpoint_trajectory initialized
[ INFO] [1638395703.344360266]: Plugin setpoint_velocity loaded
[ INFO] [1638395703.367947169]: Plugin setpoint_velocity initialized
[ INFO] [1638395703.368937765]: Plugin sys_status loaded
[ INFO] [1638395703.417009248]: Plugin sys_status initialized
[ INFO] [1638395703.417605720]: Plugin sys_time loaded
[ INFO] [1638395703.442489267]: TM: Timesync mode: MAVLINK
[ INFO] [1638395703.448472531]: Plugin sys_time initialized
[ INFO] [1638395703.448910094]: Plugin trajectory loaded
[ INFO] [1638395703.471706926]: Plugin trajectory initialized
[ INFO] [1638395703.472253761]: Plugin vfr_hud loaded
[ INFO] [1638395703.475015180]: Plugin vfr_hud initialized
[ INFO] [1638395703.475142110]: Plugin vibration blacklisted
[ INFO] [1638395703.475527535]: Plugin vision_pose_estimate loaded
[ INFO] [1638395703.506720865]: Plugin vision_pose_estimate initialized
[ INFO] [1638395703.507346036]: Plugin vision_speed_estimate loaded
[ INFO] [1638395703.524323045]: Plugin vision_speed_estimate initialized
[ INFO] [1638395703.524796754]: Plugin waypoint loaded
[ INFO] [1638395703.552585161]: Plugin waypoint initialized
[ INFO] [1638395703.552737768]: Plugin wheel_odometry blacklisted
[ INFO] [1638395703.553202727]: Plugin wind_estimation loaded
[ INFO] [1638395703.555951541]: Plugin wind_estimation initialized
[ INFO] [1638395703.556117170]: Autostarting mavlink via USB on PX4
[ INFO] [1638395703.556476553]: Built-in SIMD instructions: ARM NEON
[ INFO] [1638395703.556580358]: Built-in MAVLink package version: 2021.9.9
[ INFO] [1638395703.556662443]: Known MAVLink dialects: common ardupilotmega ASLUAV all development icarous matrixpilot paparazzi standard uAvionix ualberta
[ INFO] [1638395703.556755101]: MAVROS started. MY ID 1.240, TARGET ID 1.1
[ INFO] [1638395703.559515426]: IMU: High resolution IMU detected!
[ INFO] [1638395703.561354115]: IMU: Attitude quaternion IMU detected!
[ INFO] [1638395704.355271431]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ INFO] [1638395704.361605745]: IMU: High resolution IMU detected!
[ INFO] [1638395704.362142737]: IMU: Attitude quaternion IMU detected!
[ INFO] [1638395705.387325951]: GF: Using MISSION_ITEM_INT
[ INFO] [1638395705.387669293]: RP: Using MISSION_ITEM_INT
[ INFO] [1638395705.387907475]: WP: Using MISSION_ITEM_INT
[ INFO] [1638395705.388038780]: VER: 1.1: Capabilities         0x000000000000e4ef
[ INFO] [1638395705.388231806]: VER: 1.1: Flight software:     010c03ff (2e8918da66000000)
[ INFO] [1638395705.388440352]: VER: 1.1: Middleware software: 010c03ff (2e8918da66000000)
[ INFO] [1638395705.388649940]: VER: 1.1: OS software:         080200ff (bf660cba2af81f05)
[ INFO] [1638395705.388914269]: VER: 1.1: Board hardware:      00000032
[ INFO] [1638395705.389123701]: VER: 1.1: VID/PID:             26ac:0032
[ INFO] [1638395705.389349957]: VER: 1.1: UID:                 4e30500220333135
[ WARN] [1638395705.390009816]: CMD: Unexpected command 520, result 0
[ INFO] [1638395714.359199976]: HP: requesting home position
[ INFO] [1638395719.360039776]: GF: mission received
[ INFO] [1638395719.361151468]: RP: mission received
[ INFO] [1638395719.362129928]: WP: mission received
[ INFO] [1638395724.358330596]: HP: requesting home position
[ INFO] [1638395734.358224255]: HP: requesting home position
[ INFO] [1638395744.358394118]: HP: requesting home position

Diagnostics

header: 
  seq: 28
  stamp: 
    secs: 1638396078
    nsecs: 503925204
  frame_id: ''
status: 
  - 
    level: 0
    name: "mavros: FCU connection"
    message: "connected"
    hardware_id: "/dev/ttyTHS1:921600"
    values: 
      - 
        key: "Received packets:"
        value: "10611"
      - 
        key: "Dropped packets:"
        value: "0"
      - 
        key: "Buffer overruns:"
        value: "0"
      - 
        key: "Parse errors:"
        value: "0"
      - 
        key: "Rx sequence number:"
        value: "200"
      - 
        key: "Tx sequence number:"
        value: "0"
      - 
        key: "Rx total bytes:"
        value: "660277"
      - 
        key: "Tx total bytes:"
        value: "18629"
      - 
        key: "Rx speed:"
        value: "20332.000000"
      - 
        key: "Tx speed:"
        value: "724.000000"
  - 
    level: 0
    name: "mavros: GPS"
    message: "3D fix"
    hardware_id: "/dev/ttyTHS1:921600"
    values: 
      - 
        key: "Satellites visible"
        value: "5"
      - 
        key: "Fix type"
        value: "3"
      - 
        key: "EPH (m)"
        value: "0.00"
      - 
        key: "EPV (m)"
        value: "0.00"
  - 
    level: 0
    name: "mavros: Heartbeat"
    message: "Normal"
    hardware_id: "/dev/ttyTHS1:921600"
    values: 
      - 
        key: "Heartbeats since startup"
        value: "30"
      - 
        key: "Frequency (Hz)"
        value: "1.039932"
      - 
        key: "Vehicle type"
        value: "Quadrotor"
      - 
        key: "Autopilot type"
        value: "PX4 Autopilot"
      - 
        key: "Mode"
        value: "MANUAL"
      - 
        key: "System status"
        value: "Standby"
  - 
    level: 2
    name: "mavros: System"
    message: "Sensor health"
    hardware_id: "/dev/ttyTHS1:921600"
    values: 
      - 
        key: "Sensor present"
        value: "0x1220802C"
      - 
        key: "Sensor enabled"
        value: "0x1221800C"
      - 
        key: "Sensor health"
        value: "0x1226800F"
      - 
        key: "3D magnetometer"
        value: "Ok"
      - 
        key: "absolute pressure"
        value: "Ok"
      - 
        key: "motor outputs / control"
        value: "Ok"
      - 
        key: "rc receiver"
        value: "Fail"
      - 
        key: "AHRS subsystem health"
        value: "Ok"
      - 
        key: "Battery"
        value: "Ok"
      - 
        key: "pre-arm check status. Always healthy when armed"
        value: "Ok"
      - 
        key: "CPU Load (%)"
        value: "66.0"
      - 
        key: "Drop rate (%)"
        value: "0.0"
      - 
        key: "Errors comm"
        value: "0"
      - 
        key: "Errors count #1"
        value: "0"
      - 
        key: "Errors count #2"
        value: "0"
      - 
        key: "Errors count #3"
        value: "0"
      - 
        key: "Errors count #4"
        value: "0"
  - 
    level: 0
    name: "mavros: Battery"
    message: "Normal"
    hardware_id: "/dev/ttyTHS1:921600"
    values: 
      - 
        key: "Voltage"
        value: "16.63"
      - 
        key: "Current"
        value: "0.0"
      - 
        key: "Remaining"
        value: "100.0"
  - 
    level: 0
    name: "mavros: Time Sync"
    message: "Normal"
    hardware_id: "/dev/ttyTHS1:921600"
    values: 
      - 
        key: "Timesyncs since startup"
        value: "295"
      - 
        key: "Frequency (Hz)"
        value: "9.919490"
      - 
        key: "Last RTT (ms)"
        value: "6.540828"
      - 
        key: "Mean RTT (ms)"
        value: "8.352056"
      - 
        key: "Last remote time (s)"
        value: "2094.117235000"
      - 
        key: "Estimated time offset (s)"
        value: "1638393984.283438683"

Check ID

OK. I got messages from 1:1.

---
Received 5453 messages, from 1 addresses
sys:comp   list of messages
  1:1     0, 1, 2, 4, 8, 140, 141, 147, 22, 30, 31, 36, 44, 74, 331, 77, 83, 230, 105, 111, 241, 245
michaelb-sm commented 2 years ago

Edit: Added readout from MAVlink Inspector

vooon commented 2 years ago

I do not see any trouble on mavros side. Probably you need to change some firmware parameters to select mocap position source.

michaelb-sm commented 2 years ago

I'm inclined to agree, but I'm not sure which parameters in QGroundControl would help that I haven't already changed. Since I don't have a GPS module connected, GPS_1CONFIG doesn't have any obvious port to be assigned. If I set it to TELEM1 (since technically I'm sending the GPS data over that port) then it blocks communication from mavros over that port. Outside of MAV or GPS_ parameters, of which I have looked into, I'm unaware of any other parameters which would specifically grab this data (since it's supposed to be read as GPS data using fake_gps).

I know EKF2 is used for state estimation on the Mini, but i'm not very familiar with it. Is it possible that it's having trouble reading this source?

vooon commented 2 years ago

Sorry, but i never tried to setup it. So i mostly guessing. Perhaps you could find something useful here: https://docs.px4.io/v1.12/en/ros/external_position_estimation.html

Just one common thing to check: do you update header.stamp?

michaelb-sm commented 2 years ago

Thanks for the resource, looking into it now but I'm not sure if this will properly substitute a GPS signal.

I am updating header.stamp with ros::Time::now() every time it's published

bresch commented 2 years ago

Hi @michaelb-sm ,

Not sure if this is the only issue blocking you, but the data sent by your fake_gps doesn't pass the EKF requirements. This is a reason why it is not using the data (e.g.: number of satellites is 5 while the min specified by the parameter is 6 by default, see https://docs.px4.io/master/en/advanced_config/tuning_the_ecl_ekf.html#gnss-performance-requirements). So you can change the data you send using your fake GPS or relax the EKF requirements (EKF2_REQ_xxx) or disable some checks using EKF2_GPS_CHECK.