mavlink / mavros

MAVLink to ROS gateway with proxy for Ground Control Station
Other
884 stars 992 forks source link

Odometry Data from Odroid VIO not being sent to Pixhawk #1526

Open nabatta opened 3 years ago

nabatta commented 3 years ago

Issue details

Hello! I am attempting to use the Auterion VIO node on my Odroid H2+. The VIO package seems to be working fine as I can echo /mavros/odometry/out and I can see the pose change as I move the camera around.

However, when I boot up QGC and go to the Mavlink Inspector, I am not getting any messages from the Odroid. I can see an ODOMETRY message but it is only being generated by the IMU's on the Pixhawk. However, if I run "rosrun mavros mavsafety arm" from the terminal, QGC responds to the command. So some messages must be getting through. I can also echo the heartbeat topic (/mavros/state) from the terminal and get a response. But there is no heartbeat message showing up in QGC from the Odroid (only from the Pixhawk).

I am also getting a message saying "HP: requesting home position" so I am not sure if this is causing the issue but I do not think so. I am relatively new to all this so hopefully this is a simple question. Thank you for the help!

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

SUMMARY
========

CLEAR PARAMETERS
 * /mavros/

PARAMETERS
 * /camera/realsense2_camera/accel_fps: 62
 * /camera/realsense2_camera/accel_frame_id: camera_accel_frame
 * /camera/realsense2_camera/accel_optical_frame_id: camera_accel_opti...
 * /camera/realsense2_camera/align_depth: False
 * /camera/realsense2_camera/aligned_depth_to_color_frame_id: camera_aligned_de...
 * /camera/realsense2_camera/aligned_depth_to_fisheye1_frame_id: camera_aligned_de...
 * /camera/realsense2_camera/aligned_depth_to_fisheye2_frame_id: camera_aligned_de...
 * /camera/realsense2_camera/aligned_depth_to_fisheye_frame_id: camera_aligned_de...
 * /camera/realsense2_camera/aligned_depth_to_infra1_frame_id: camera_aligned_de...
 * /camera/realsense2_camera/aligned_depth_to_infra2_frame_id: camera_aligned_de...
 * /camera/realsense2_camera/allow_no_texture_points: False
 * /camera/realsense2_camera/base_frame_id: camera_link
 * /camera/realsense2_camera/calib_odom_file: 
 * /camera/realsense2_camera/clip_distance: -1.0
 * /camera/realsense2_camera/color_fps: 30
 * /camera/realsense2_camera/color_frame_id: camera_color_frame
 * /camera/realsense2_camera/color_height: 480
 * /camera/realsense2_camera/color_optical_frame_id: camera_color_opti...
 * /camera/realsense2_camera/color_width: 640
 * /camera/realsense2_camera/depth_fps: 30
 * /camera/realsense2_camera/depth_frame_id: camera_depth_frame
 * /camera/realsense2_camera/depth_height: 480
 * /camera/realsense2_camera/depth_optical_frame_id: camera_depth_opti...
 * /camera/realsense2_camera/depth_width: 640
 * /camera/realsense2_camera/device_type: t265
 * /camera/realsense2_camera/enable_accel: False
 * /camera/realsense2_camera/enable_color: True
 * /camera/realsense2_camera/enable_depth: True
 * /camera/realsense2_camera/enable_fisheye1: True
 * /camera/realsense2_camera/enable_fisheye2: True
 * /camera/realsense2_camera/enable_fisheye: False
 * /camera/realsense2_camera/enable_gyro: False
 * /camera/realsense2_camera/enable_infra1: False
 * /camera/realsense2_camera/enable_infra2: False
 * /camera/realsense2_camera/enable_infra: False
 * /camera/realsense2_camera/enable_pointcloud: False
 * /camera/realsense2_camera/enable_pose: True
 * /camera/realsense2_camera/enable_sync: False
 * /camera/realsense2_camera/filters: 
 * /camera/realsense2_camera/fisheye1_frame_id: camera_fisheye1_f...
 * /camera/realsense2_camera/fisheye1_optical_frame_id: camera_fisheye1_o...
 * /camera/realsense2_camera/fisheye2_frame_id: camera_fisheye2_f...
 * /camera/realsense2_camera/fisheye2_optical_frame_id: camera_fisheye2_o...
 * /camera/realsense2_camera/fisheye_fps: 30
 * /camera/realsense2_camera/fisheye_frame_id: camera_fisheye_frame
 * /camera/realsense2_camera/fisheye_height: 800
 * /camera/realsense2_camera/fisheye_optical_frame_id: camera_fisheye_op...
 * /camera/realsense2_camera/fisheye_width: 848
 * /camera/realsense2_camera/gyro_fps: 200
 * /camera/realsense2_camera/gyro_frame_id: camera_gyro_frame
 * /camera/realsense2_camera/gyro_optical_frame_id: camera_gyro_optic...
 * /camera/realsense2_camera/imu_optical_frame_id: camera_imu_optica...
 * /camera/realsense2_camera/infra1_frame_id: camera_infra1_frame
 * /camera/realsense2_camera/infra1_optical_frame_id: camera_infra1_opt...
 * /camera/realsense2_camera/infra2_frame_id: camera_infra2_frame
 * /camera/realsense2_camera/infra2_optical_frame_id: camera_infra2_opt...
 * /camera/realsense2_camera/infra_fps: 30
 * /camera/realsense2_camera/infra_height: 480
 * /camera/realsense2_camera/infra_width: 640
 * /camera/realsense2_camera/initial_reset: False
 * /camera/realsense2_camera/json_file_path: 
 * /camera/realsense2_camera/linear_accel_cov: 0.01
 * /camera/realsense2_camera/odom_frame_id: camera_odom_frame
 * /camera/realsense2_camera/pointcloud_texture_index: 0
 * /camera/realsense2_camera/pointcloud_texture_stream: RS2_STREAM_COLOR
 * /camera/realsense2_camera/pose_frame_id: camera_pose_frame
 * /camera/realsense2_camera/pose_optical_frame_id: camera_pose_optic...
 * /camera/realsense2_camera/publish_odom_tf: False
 * /camera/realsense2_camera/publish_tf: True
 * /camera/realsense2_camera/rosbag_filename: 
 * /camera/realsense2_camera/serial_no: 
 * /camera/realsense2_camera/tf_publish_rate: 0.0
 * /camera/realsense2_camera/topic_odom_in: camera/odom_in
 * /camera/realsense2_camera/unite_imu_method: 
 * /camera/realsense2_camera/usb_port_id: 
 * /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/id: 2
 * /mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270
 * /mavros/distance_sensor/sonar_1_sub/subscriber: True
 * /mavros/fake_gps/eph: 2.0
 * /mavros/fake_gps/epv: 2.0
 * /mavros/fake_gps/fix_type: 3
 * /mavros/fake_gps/geo_origin/alt: 408.0
 * /mavros/fake_gps/geo_origin/lat: 47.3667
 * /mavros/fake_gps/geo_origin/lon: 8.55
 * /mavros/fake_gps/gps_rate: 5.0
 * /mavros/fake_gps/mocap_transform: True
 * /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_mocap: True
 * /mavros/fake_gps/use_vision: False
 * /mavros/fcu_protocol: v2.0
 * /mavros/fcu_url: /dev/ttyUSB0: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
 * /px4_realsense_bridge_node/input_topic: ['/camera/odom/sa...
 * /rosdistro: melodic
 * /rosversion: 1.14.10

NODES
  /
    drop_image1 (topic_tools/drop)
    drop_image2 (topic_tools/drop)
    mavros (mavros/mavros_node)
    odom_throttler (topic_tools/drop)
    px4_realsense_bridge_node (px4_realsense_bridge/px4_realsense_bridge_node)
    tf_baseLink_cameraPose (tf/static_transform_publisher)
    tf_odom_cameraOdom (tf/static_transform_publisher)
  /camera/
    realsense2_camera (nodelet/nodelet)
    realsense2_camera_manager (nodelet/nodelet)

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

setting /run_id to 43bf8848-617e-11eb-b620-ffd3edc95d86
process[rosout-1]: started with pid [3116]
started core service [/rosout]
process[tf_baseLink_cameraPose-2]: started with pid [3124]
process[tf_odom_cameraOdom-3]: started with pid [3125]
process[drop_image1-4]: started with pid [3126]
process[drop_image2-5]: started with pid [3132]
process[odom_throttler-6]: started with pid [3139]
process[camera/realsense2_camera_manager-7]: started with pid [3144]
process[camera/realsense2_camera-8]: started with pid [3150]
process[px4_realsense_bridge_node-9]: started with pid [3155]
process[mavros-10]: started with pid [3157]
[ INFO] [1611848051.628008078]: Initializing nodelet with 4 worker threads.
[ INFO] [1611848051.727407631]: FCU URL: /dev/ttyUSB0:921600
[ INFO] [1611848051.730141588]: serial0: device: /dev/ttyUSB0 @ 921600 bps
[ INFO] [1611848051.731365707]: GCS bridge disabled
[ INFO] [1611848051.828041194]: RealSense ROS v2.2.18
[ INFO] [1611848051.828106683]: Built with LibRealSense v2.39.0
[ INFO] [1611848051.828154781]: Running with LibRealSense v2.39.0
[ INFO] [1611848051.828494769]: Plugin 3dr_radio loaded
[ INFO] [1611848051.832216616]: Plugin 3dr_radio initialized
[ INFO] [1611848051.832329811]: Plugin actuator_control loaded
[ INFO] [1611848051.839896381]: Plugin actuator_control initialized
[ INFO] [1611848051.853485153]: Plugin adsb loaded
[ INFO] [1611848051.860411994]:  
[ INFO] [1611848051.862376088]: Plugin adsb initialized
[ INFO] [1611848051.862561580]: Plugin altitude loaded
[ INFO] [1611848051.863662760]: Plugin altitude initialized
[ INFO] [1611848051.863786281]: Plugin cam_imu_sync loaded
[ INFO] [1611848051.865114349]: Plugin cam_imu_sync initialized
[ INFO] [1611848051.865519311]: Plugin command loaded
[ INFO] [1611848051.872536860]: Plugin command initialized
[ INFO] [1611848051.872733773]: Plugin companion_process_status loaded
[ INFO] [1611848051.875550041]: Plugin companion_process_status initialized
[ INFO] [1611848051.875705142]: Plugin debug_value loaded
[ INFO] [1611848051.877426433]: Device with serial number 952322110823 was found.

[ INFO] [1611848051.877506826]: Device with physical ID 2-2-2 was found.
[ INFO] [1611848051.877659864]: Device with name Intel RealSense T265 was found.
[ INFO] [1611848051.878388801]: Device with port number 2-2 was found.
[ INFO] [1611848051.884646271]: Plugin debug_value initialized
[ INFO] [1611848051.884720998]: Plugin distance_sensor blacklisted
[ INFO] [1611848051.884888795]: Plugin esc_status loaded
[ INFO] [1611848051.887519583]: No calib_odom_file. No input odometry accepted.
[ INFO] [1611848051.888006225]: getParameters...
[ INFO] [1611848051.888757456]: Plugin esc_status initialized
[ INFO] [1611848051.888961663]: Plugin fake_gps loaded
[ INFO] [1611848051.934897389]: Plugin fake_gps initialized
[ INFO] [1611848051.935176294]: Plugin ftp loaded
[ INFO] [1611848051.963779539]: Plugin ftp initialized
[ INFO] [1611848051.963993545]: Plugin global_position loaded
[ INFO] [1611848052.013506064]: Plugin global_position initialized
[ INFO] [1611848052.013703588]: Plugin gps_rtk loaded
[ INFO] [1611848052.017532703]: Plugin gps_rtk initialized
[ INFO] [1611848052.017875233]: Plugin gps_status loaded
[ INFO] [1611848052.024244167]: Plugin gps_status initialized
[ INFO] [1611848052.024466893]: Plugin hil loaded
[ INFO] [1611848052.053146423]: setupDevice...
[ INFO] [1611848052.053212965]: JSON file is not provided
[ INFO] [1611848052.053260029]: ROS Node Namespace: camera
[ INFO] [1611848052.053299130]: Device Name: Intel RealSense T265
[ INFO] [1611848052.053333300]: Device Serial No: 952322110823
[ INFO] [1611848052.053385250]: Device physical port: 2-2-2
[ INFO] [1611848052.053420122]: Device FW version: 0.2.0.951
[ INFO] [1611848052.053467718]: Device Product ID: 0x0B37
[ INFO] [1611848052.053503150]: Enable PointCloud: Off
[ INFO] [1611848052.053547738]: Align Depth: Off
[ INFO] [1611848052.053580839]: Sync Mode: Off
[ INFO] [1611848052.053629665]: Device Sensors: 
[ INFO] [1611848052.053783032]: Tracking Module was found.
[ INFO] [1611848052.053850150]: (Depth, 0) sensor isn't supported by current device! -- Skipping...
[ INFO] [1611848052.053886581]: (Color, 0) sensor isn't supported by current device! -- Skipping...
[ INFO] [1611848052.053938623]: num_filters: 0
[ INFO] [1611848052.053972563]: Setting Dynamic reconfig parameters.
[ INFO] [1611848052.060319039]: Plugin hil initialized
[ WARN] [1611848052.060764551]: Param '/camera/tracking_module/frames_queue_size' has value 256 that is not in range [0, 32]. Removing this parameter from dynamic reconfigure options.
[ INFO] [1611848052.060835874]: Plugin home_position loaded
[ INFO] [1611848052.070266988]: Plugin home_position initialized
[ INFO] [1611848052.070477186]: Plugin imu loaded
[ INFO] [1611848052.078932680]: Done Setting Dynamic reconfig parameters.
[ INFO] [1611848052.084314936]: Plugin imu initialized
[ INFO] [1611848052.084512992]: Plugin landing_target loaded
[ INFO] [1611848052.100129815]: fisheye1 stream is enabled - width: 848, height: 800, fps: 30, Format: Y8
[ INFO] [1611848052.100659924]: Plugin landing_target initialized
[ INFO] [1611848052.100846238]: Plugin local_position loaded
[ INFO] [1611848052.100880821]: fisheye2 stream is enabled - width: 848, height: 800, fps: 30, Format: Y8
[ INFO] [1611848052.100952377]: setupPublishers...
[ INFO] [1611848052.103765020]: Expected frequency for fisheye1 = 30.00000
[ INFO] [1611848052.109618429]: Plugin local_position initialized
[ INFO] [1611848052.109826486]: Plugin log_transfer loaded
[ INFO] [1611848052.116527952]: Plugin log_transfer initialized
[ INFO] [1611848052.116742090]: Plugin manual_control loaded
[ INFO] [1611848052.124644915]: Plugin manual_control initialized
[ INFO] [1611848052.124845908]: Plugin mocap_pose_estimate loaded
[ INFO] [1611848052.132569076]: Plugin mocap_pose_estimate initialized
[ INFO] [1611848052.132946474]: Plugin mount_control loaded
[ INFO] [1611848052.139364956]: Plugin mount_control initialized
[ INFO] [1611848052.139575460]: Plugin obstacle_distance loaded
[ INFO] [1611848052.146649670]: Plugin obstacle_distance initialized
[ INFO] [1611848052.146841891]: Plugin odom loaded
[ INFO] [1611848052.157471653]: Plugin odom initialized
[ INFO] [1611848052.157697796]: Plugin onboard_computer_status loaded
[ INFO] [1611848052.161924383]: Plugin onboard_computer_status initialized
[ INFO] [1611848052.162277589]: Plugin param loaded
[ INFO] [1611848052.169237362]: Plugin param initialized
[ INFO] [1611848052.169420857]: Plugin play_tune loaded
[ INFO] [1611848052.172148581]: Plugin play_tune initialized
[ INFO] [1611848052.172385144]: Plugin px4flow loaded
[ INFO] [1611848052.185835155]: Plugin px4flow initialized
[ INFO] [1611848052.185933090]: Plugin rangefinder blacklisted
[ INFO] [1611848052.186256593]: Plugin rc_io loaded
[ INFO] [1611848052.196290013]: Plugin rc_io initialized
[ INFO] [1611848052.196365720]: Plugin safety_area blacklisted
[ INFO] [1611848052.196550685]: Plugin setpoint_accel loaded
[ INFO] [1611848052.202006758]: Expected frequency for fisheye2 = 30.00000
[ INFO] [1611848052.203853756]: Plugin setpoint_accel initialized
[ INFO] [1611848052.204102790]: Plugin setpoint_attitude loaded
[ INFO] [1611848052.227706048]: Plugin setpoint_attitude initialized
[ INFO] [1611848052.227939005]: Plugin setpoint_position loaded
[ INFO] [1611848052.272253204]: Plugin setpoint_position initialized
[ INFO] [1611848052.272524878]: Plugin setpoint_raw loaded
[ INFO] [1611848052.290353497]: setupStreams...
[ INFO] [1611848052.290488256]: insert Fisheye to Tracking Module
[ INFO] [1611848052.290566116]: insert Fisheye to Tracking Module
[ INFO] [1611848052.290617145]: insert Pose to Tracking Module
[ INFO] [1611848052.293061942]: Plugin setpoint_raw initialized
[ INFO] [1611848052.293276756]: Plugin setpoint_trajectory loaded
[ INFO] [1611848052.298418328]: Plugin setpoint_trajectory initialized
[ INFO] [1611848052.298589906]: Plugin setpoint_velocity loaded
[ INFO] [1611848052.306992100]: Plugin setpoint_velocity initialized
[ INFO] [1611848052.307280851]: Plugin sys_status loaded
[ INFO] [1611848052.321529381]: Plugin sys_status initialized
[ INFO] [1611848052.321734498]: Plugin sys_time loaded
[ INFO] [1611848052.327802884]: TM: Timesync mode: MAVLINK
[ INFO] [1611848052.329903644]: Plugin sys_time initialized
[ INFO] [1611848052.330150076]: Plugin trajectory loaded
[ INFO] [1611848052.338305571]: Plugin trajectory initialized
[ INFO] [1611848052.338562304]: Plugin vfr_hud loaded
[ INFO] [1611848052.339446869]: Plugin vfr_hud initialized
[ INFO] [1611848052.339519282]: Plugin vibration blacklisted
[ INFO] [1611848052.339693781]: Plugin vision_pose_estimate loaded
[ INFO] [1611848052.349532760]: Plugin vision_pose_estimate initialized
[ INFO] [1611848052.349720071]: Plugin vision_speed_estimate loaded
[ INFO] [1611848052.354847128]: Plugin vision_speed_estimate initialized
[ INFO] [1611848052.355112330]: Plugin waypoint loaded
[ INFO] [1611848052.363765158]: Plugin waypoint initialized
[ INFO] [1611848052.363864773]: Plugin wheel_odometry blacklisted
[ INFO] [1611848052.364066566]: Plugin wind_estimation loaded
[ INFO] [1611848052.365194280]: Plugin wind_estimation initialized
[ INFO] [1611848052.365279943]: Autostarting mavlink via USB on PX4
[ INFO] [1611848052.365361849]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1611848052.365406571]: Built-in MAVLink package version: 2020.10.11
[ INFO] [1611848052.365475473]: Known MAVLink dialects: common ardupilotmega ASLUAV all autoquad icarous matrixpilot paparazzi standard uAvionix ualberta
[ INFO] [1611848052.365528736]: MAVROS started. MY ID 1.240, TARGET ID 1.1
[ INFO] [1611848052.375857701]: SELECTED BASE:Pose, 0
[ INFO] [1611848052.376435548]: RealSense Node Is Up!
[ INFO] [1611848052.385712262]: IMU: High resolution IMU detected!
[ INFO] [1611848052.386139144]: IMU: Attitude quaternion IMU detected!
advertised as /camera/fisheye1/image_raw_drop
advertised as /camera/fisheye2/image_raw_drop
[ INFO] [1611848052.876553533]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ INFO] [1611848052.882422425]: IMU: Attitude quaternion IMU detected!
[ INFO] [1611848052.886815914]: IMU: High resolution IMU detected!
[ INFO] [1611848053.884055391]: WP: Using MISSION_ITEM_INT
[ INFO] [1611848053.884256192]: VER: 1.1: Capabilities         0x000000000000e4ef
[ INFO] [1611848053.884371902]: VER: 1.1: Flight software:     010902ff (106905871d000000)
[ INFO] [1611848053.884475460]: VER: 1.1: Middleware software: 010902ff (106905871d000000)
[ INFO] [1611848053.884579234]: VER: 1.1: OS software:         071c00ff (423371c7d4012e72)
[ INFO] [1611848053.884675023]: VER: 1.1: Board hardware:      00000011
[ INFO] [1611848053.884760074]: VER: 1.1: VID/PID:             26ac:0011
[ INFO] [1611848053.884843514]: VER: 1.1: UID:                 3238511130313538
[ WARN] [1611848053.885603685]: CMD: Unexpected command 520, result 0
[ INFO] [1611848062.876970526]: HP: requesting home position
[ WARN] [1611848067.433412681]: PR: request param #19 timeout, retries left 2, and 14 params still missing
[ INFO] [1611848067.882463467]: WP: mission received
[ INFO] [1611848072.876923831]: HP: requesting home position
[ INFO] [1611848082.877000879]: HP: requesting home position
[ INFO] [1611848092.877417268]: HP: requesting home position

Diagnostics

header: 
  seq: 38
  stamp: 
    secs: 1611848290
    nsecs: 961334968
  frame_id: ''
status: 
  - 
    level: 0
    name: "mavros: FCU connection"
    message: "connected"
    hardware_id: "/dev/ttyUSB0:921600"
    values: 
      - 
        key: "Received packets:"
        value: "16060"
      - 
        key: "Dropped packets:"
        value: "0"
      - 
        key: "Buffer overruns:"
        value: "0"
      - 
        key: "Parse errors:"
        value: "0"
      - 
        key: "Rx sequence number:"
        value: "131"
      - 
        key: "Tx sequence number:"
        value: "0"
      - 
        key: "Rx total bytes:"
        value: "968363"
      - 
        key: "Tx total bytes:"
        value: "264798"
      - 
        key: "Rx speed:"
        value: "32556.000000"
      - 
        key: "Tx speed:"
        value: "9124.000000"
  - 
    level: 2
    name: "mavros: GPS"
    message: "No satellites"
    hardware_id: "/dev/ttyUSB0:921600"
    values: 
      - 
        key: "Satellites visible"
        value: "0"
      - 
        key: "Fix type"
        value: "0"
      - 
        key: "EPH (m)"
        value: "Unknown"
      - 
        key: "EPV (m)"
        value: "Unknown"
  - 
    level: 0
    name: "mavros: Heartbeat"
    message: "Normal"
    hardware_id: "/dev/ttyUSB0:921600"
    values: 
      - 
        key: "Heartbeats since startup"
        value: "43"
      - 
        key: "Frequency (Hz)"
        value: "1.037050"
      - 
        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/ttyUSB0:921600"
    values: 
      - 
        key: "Sensor present"
        value: "0x000E002F"
      - 
        key: "Sensor enabled"
        value: "0x0021000F"
      - 
        key: "Sensor health"
        value: "0x000E002F"
      - 
        key: "3D gyro"
        value: "Ok"
      - 
        key: "3D accelerometer"
        value: "Ok"
      - 
        key: "3D magnetometer"
        value: "Ok"
      - 
        key: "absolute pressure"
        value: "Ok"
      - 
        key: "rc receiver"
        value: "Fail"
      - 
        key: "AHRS subsystem health"
        value: "Fail"
      - 
        key: "CPU Load (%)"
        value: "71.8"
      - 
        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/ttyUSB0:921600"
    values: 
      - 
        key: "Voltage"
        value: "65.54"
      - 
        key: "Current"
        value: "-0.0"
      - 
        key: "Remaining"
        value: "-1.0"
  - 
    level: 0
    name: "mavros: Time Sync"
    message: "Normal"
    hardware_id: "/dev/ttyUSB0:921600"
    values: 
      - 
        key: "Timesyncs since startup"
        value: "428"
      - 
        key: "Frequency (Hz)"
        value: "9.926076"
      - 
        key: "Last RTT (ms)"
        value: "5.119273"
      - 
        key: "Mean RTT (ms)"
        value: "4.342858"
      - 
        key: "Last remote time (s)"
        value: "388.537465000"
      - 
        key: "Estimated time offset (s)"
        value: "1611847902.391566277"

Check ID

OK. I got messages from 1:1.

---
Received 5274 messages, from 1 addresses
sys:comp   list of messages
  1:1     0, 1, 2, 4, 140, 141, 147, 30, 31, 32, 36, 74, 331, 76, 77, 83, 340, 230, 105, 111, 241, 245
antonio-sc66 commented 3 years ago

Hi @nabatta I think the problem is that you might be using a MAVROS version in which the odom plugin doesn't send the proper estimator_type and PX4 discards that message. This was solved here #1524. If you can try to test the current master branch of MAVROS.

nabatta commented 3 years ago

@antonio-sc66 I have MAVROS 1.5.1. Would this issue apply to that version? It seems like the problem described in #1524 is definitely what I am experiencing. However, when I looked for the odom.cpp file, it does not exist for some reason.

antonio-sc66 commented 3 years ago

@nabatta yes, that problem applies to 1.5.1. It has not been released and tagged yet, you have to download this repository and compile it yourself if you want to use it for the moment. The odom.cpp file should be in this path (mavros/mavros_extras/src/plugins/odom.cpp). Another option if you need to get it working now is to downgrade PX4 to the latest 1.10 version. This problem started in PX4 1.11 as it now checks the estimator_type and before 1.11 it didn't.

nabatta commented 3 years ago

@antonio-sc66 I am currently using PX4 1.9.2. Do you know if this version also had the issue?

antonio-sc66 commented 3 years ago

@nabatta I don't know. I've been using the odom plugin and the vision_pose_estimate plugin and they both worked with PX4 1.10.1 and 1.11.3, but I haven't used them with Auterion VIO, I was sending the data from other algorithms. Make sure you have MAV_ODOM_LP=1 so you can see the messages in QGroundControl and recheck the EKF2_AID_MASK

dagar commented 3 years ago

Here's a fix for PX4. https://github.com/PX4/PX4-Autopilot/pull/16774

nabatta commented 3 years ago

@antonio-sc66 Just downloaded the newest version of mavros from source but am still having the same issue. I doublechecked and the 2 lines in odom.cpp are definitely there. When I echo the topic /mavros/odometry/out, I can see the values change as I move the camera. However, the frame_id is "camera_odom_frame". I think something may be wrong with a frame_id?

nabatta commented 3 years ago

@antonio-sc66 Just got it working! I simply updated to PX4 1.11.3 and that fixed the issue. The older firmware was still causing some issues even with the new fix to the mavros code. Thank you for the help!