Visual Odometry, /mavros/local_position/pose and no VISION_POSITION_ESTIMATE message in Mavlink Inspector

I’m trying to setup visual odometry for indoor drone with Pixhawk 1 (2.4.8). I cannot get /mavros/local_position/pose topic and no VISION_POSITION_ESTIMATE message is seen in mavlink Inspector.

  1. firmware flashed = fmuv3, Arducopter 4.4.4
  2. TELEM2 set to Mavlink2 @ 921600, connected to laptop via USB to TTL
  3. Camera used Realsense d435
  4. using ROS noetic

Below are the Configuration in Mission planner for visual odometry.
SERIAL2_PROTOCOL = 2
SERIAL2_BAUD = 921600
AHRS_EKF_TYPE = 3
EK3_ENABLE = 1
EK2_ENABLE = 0
GPS_TYPE = 0
EK3_SRC1_POSXY = 6 (External Nav)
EK3_SRC1_POSZ = 6
EK3_SRC1_VELXY = 6
EK3_SRC1_VELZ = 6
EK3_SRC1_YAW = 6
COMPASS_USE = 0
COMPASS_USE2 = 0
COMPASS_USE3 = 0
VISO_TYPE = 1 (Mavlink)

Below are the Commands used to run MAVROS on laptop and connect to FC

  1. run mavros
roslaunch mavros apm.launch fcu_url:=/dev/ttyUSB0:921600 gcs_url:="tcp-l://192.168.88.154:14855@14855"
  1. Getting Visual Odometry from RTAB using below tutorial
http://wiki.ros.org/rtabmap_ros/Tutorials/StereoHandHeldMapping
  1. running vision_to_mavros node to provide the rtab odom to mavros
roslaunch vision_to_mavros t265_tf_to_mavros.launch

cotent of t265_tf_to_mavros.launch

<launch>

    <!-- This node will launch frame conversion from vision pose (tf) to mavros pose -->
    <!-- <arg name="target_frame_id"   default="/camera_odom_frame" /> -->
    <arg name="target_frame_id"   default="/odom" /> 
    <param name="target_frame_id"   value="$(arg target_frame_id)" />

    <arg name="source_frame_id"   default="/camera_link" />
    <param name="source_frame_id"   value="$(arg source_frame_id)" />

    <param name="output_rate"       value="30" />

    <!-- Two steps alignment: 
    1) r,p,y: align current camera frame with default camera frame (x forward, y left, z up)
    2) gamma: align default camera frame's x axis with world y axis
    Frontfacing:
        Forward, USB port to the right (default): r = 0,          p = 0,          y = 0,  gamma = -1.5707963 
        Forward, USB port to the left           : r = 3.1415926,  p = 0,          y = 0,  gamma = -1.5707963 
    Downfacing: you need to tilt the vehicle's nose up a little (not flat) when launch the T265 realsense-ros node, otherwise the initial yaw will be randomized, read here: https://github.com/IntelRealSense/librealsense/issues/4080
    Tilt the vehicle to any other sides and the yaw might not be as stable.
        Downfacing, USB port to the right :       r = 0,          p = -1.5707963, y = 0,  gamma = -1.5707963
        Downfacing, USB port to the left  :       r = 3.1415926,  p = -1.5707963, y = 0,  gamma = -1.5707963
        Downfacing, USB port to the back  :       r = -1.5707963, p = -1.5707963, y = 0,  gamma = -1.5707963          
        Downfacing, USB port to the front :       r = 1.5707963,  p = -1.5707963, y = 0,  gamma = -1.5707963
    -->
    <param name="roll_cam"          value="0" />
    <param name="pitch_cam"         value="0" />
    <param name="yaw_cam"           value="0" />
    <param name="gamma_world"       value="-1.5707963" />

    <node pkg="vision_to_mavros" type="vision_to_mavros_node" name="t265_to_mavros" output="screen" >
        <remap from="vision_pose" to="/mavros/vision_pose/pose" />
    </node>
</launch>
$ rostopic echo /rtabmap/odom -n1
header: 
  seq: 206834
  stamp: 
    secs: 1711466051
    nsecs:  91943741
  frame_id: "odom"
child_frame_id: "camera_link"
pose: 
  pose: 
    position: 
      x: -0.005919177085161209
      y: 1.178796410560608
      z: 0.08733992278575897
    orientation: 
      x: 0.08607737498181255
      y: 0.016036544153318507
      z: -0.12494893969624359
      w: 0.9882921011708247
  covariance: [8.757750011631288e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.757750011631288e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.757750011631288e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0004799903411627748, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0004799903411627748, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0004799903411627748]
twist: 
  twist: 
    linear: 
      x: -0.05208556726574898
      y: 0.03203533589839935
      z: -0.01812843047082424
    angular: 
      x: 0.004015828482806683
      y: -0.0017974739894270897
      z: -0.017067940905690193
  covariance: [4.378875005815644e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.378875005815644e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.378875005815644e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002399951705813874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002399951705813874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002399951705813874]
---
  1. pose data is published on topic /mavros/vision_pose/pose
  2. origin is succefully set
rosrun vision_to_mavros set_origin.py

ISSUES :slight_smile:

  1. after following above steps, no data is published on /mavros/local_position/pose topic.
  2. no VISION_POSITION_ESTIMATE message is seen in Mavlink inspector.

Special Case :slight_smile:

  1. only when Mission planner is connected using TCP while mavros apm.launch is still running, then suddenly /mavros/local_position/pose starts publishing data at around 2Hz.

OUTPUT:

  1. when only apm.launch is running
roslaunch mavros apm.launch fcu_url:=/dev/ttyUSB0:921600 gcs_url:="tcp-l://192.168.88.154:14855@14855"
... logging to /.ros/log/b2d15f5a-eb54-11ee-a938-436c2ef6dce3/roslaunch-void-362324.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

SUMMARY
========

CLEAR PARAMETERS
 * /mavros/

PARAMETERS
 * /mavros/cmd/use_comp_id_system_control: False
 * /mavros/conn/heartbeat_mav_type: ONBOARD_CONTROLLER
 * /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/rangefinder_pub/field_of_view: 0.0
 * /mavros/distance_sensor/rangefinder_pub/frame_id: lidar
 * /mavros/distance_sensor/rangefinder_pub/id: 0
 * /mavros/distance_sensor/rangefinder_pub/send_tf: False
 * /mavros/distance_sensor/rangefinder_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/rangefinder_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/rangefinder_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/rangefinder_sub/id: 1
 * /mavros/distance_sensor/rangefinder_sub/orientation: PITCH_270
 * /mavros/distance_sensor/rangefinder_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_id: 4
 * /mavros/fake_gps/gps_rate: 5.0
 * /mavros/fake_gps/horiz_accuracy: 0.5
 * /mavros/fake_gps/mocap_transform: False
 * /mavros/fake_gps/mocap_withcovariance: False
 * /mavros/fake_gps/satellites_visible: 6
 * /mavros/fake_gps/speed_accuracy: 0.0
 * /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/fake_gps/vert_accuracy: 0.5
 * /mavros/fcu_protocol: v2.0
 * /mavros/fcu_url: /dev/ttyUSB0:921600
 * /mavros/gcs_url: tcp-l://192.168.8...
 * /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/guided_target/tf/child_frame_id: target_position
 * /mavros/guided_target/tf/frame_id: map
 * /mavros/guided_target/tf/listen: False
 * /mavros/guided_target/tf/rate_limit: 50.0
 * /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/mount/debounce_s: 4.0
 * /mavros/mount/err_threshold_deg: 10.0
 * /mavros/mount/negate_measured_pitch: False
 * /mavros/mount/negate_measured_roll: False
 * /mavros/mount/negate_measured_yaw: False
 * /mavros/odometry/estimator_type: 3
 * /mavros/odometry/frame_tf/desired_frame: ned
 * /mavros/plugin_blacklist: ['actuator_contro...
 * /mavros/plugin_whitelist: ['vision_position...
 * /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: False
 * /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: map
 * /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: map
 * /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: map
 * /mavros/wheel_odometry/tf/send: True
 * /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: noetic
 * /rosversion: 1.16.0

NODES
  /
    mavros (mavros/mavros_node)

ROS_MASTER_URI=http://localhost:11311

process[mavros-1]: started with pid [362362]
[ INFO] [1711466744.985933419]: FCU URL: /dev/ttyUSB0:921600
[ INFO] [1711466744.988091491]: serial0: device: /dev/ttyUSB0 @ 921600 bps
[ INFO] [1711466744.989170387]: GCS URL: tcp-l://192.168.88.154:14855@14855
[ INFO] [1711466744.989442882]: tcp1: Bind address: 192.168.88.154:14855
[ INFO] [1711466744.996986041]: Plugin 3dr_radio loaded
[ INFO] [1711466744.998003134]: Plugin 3dr_radio initialized
[ INFO] [1711466744.998018240]: Plugin actuator_control blacklisted
[ INFO] [1711466745.001017080]: Plugin adsb loaded
[ INFO] [1711466745.002372974]: Plugin adsb initialized
[ INFO] [1711466745.002384606]: Plugin altitude blacklisted
[ INFO] [1711466745.002472508]: Plugin cam_imu_sync loaded
[ INFO] [1711466745.002779733]: Plugin cam_imu_sync initialized
[ INFO] [1711466745.002848207]: Plugin camera loaded
[ INFO] [1711466745.003166258]: Plugin camera initialized
[ INFO] [1711466745.003262895]: Plugin cellular_status loaded
[ INFO] [1711466745.004213939]: Plugin cellular_status initialized
[ INFO] [1711466745.004338272]: Plugin command loaded
[ INFO] [1711466745.007502508]: Plugin command initialized
[ INFO] [1711466745.007597985]: Plugin companion_process_status loaded
[ INFO] [1711466745.008581136]: Plugin companion_process_status initialized
[ INFO] [1711466745.008591179]: Plugin debug_value blacklisted
[ INFO] [1711466745.008685834]: Plugin distance_sensor loaded
[ INFO] [1711466745.012376463]: Plugin distance_sensor initialized
[ INFO] [1711466745.012500285]: Plugin esc_status loaded
[ INFO] [1711466745.013061868]: Plugin esc_status initialized
[ INFO] [1711466745.013166742]: Plugin esc_telemetry loaded
[ INFO] [1711466745.013528197]: Plugin esc_telemetry initialized
[ INFO] [1711466745.013643527]: Plugin fake_gps loaded
[ INFO] [1711466745.020654172]: Plugin fake_gps initialized
[ INFO] [1711466745.020668335]: Plugin ftp blacklisted
[ INFO] [1711466745.020795397]: Plugin geofence loaded
[ INFO] [1711466745.022481826]: Plugin geofence initialized
[ INFO] [1711466745.022595054]: Plugin global_position loaded
[ INFO] [1711466745.029539060]: Plugin global_position initialized
[ INFO] [1711466745.029621030]: Plugin gps_input loaded
[ INFO] [1711466745.030787066]: Plugin gps_input initialized
[ INFO] [1711466745.030849705]: Plugin gps_rtk loaded
[ INFO] [1711466745.032059184]: Plugin gps_rtk initialized
[ INFO] [1711466745.032125058]: Plugin gps_status loaded
[ INFO] [1711466745.033120789]: Plugin gps_status initialized
[ INFO] [1711466745.033188573]: Plugin guided_target loaded
[ INFO] [1711466745.035468029]: Plugin guided_target initialized
[ INFO] [1711466745.035480572]: Plugin hil blacklisted
[ INFO] [1711466745.035550366]: Plugin home_position loaded
[ INFO] [1711466745.037014210]: Plugin home_position initialized
[ INFO] [1711466745.037179229]: Plugin imu loaded
[ INFO] [1711466745.040323297]: Plugin imu initialized
[ INFO] [1711466745.040395812]: Plugin landing_target loaded
[ INFO] [1711466745.045814393]: Plugin landing_target initialized
[ INFO] [1711466745.045935831]: Plugin local_position loaded
[ INFO] [1711466745.048744313]: Plugin local_position initialized
[ INFO] [1711466745.048863154]: Plugin log_transfer loaded
[ INFO] [1711466745.051040467]: Plugin log_transfer initialized
[ INFO] [1711466745.051176023]: Plugin mag_calibration_status loaded
[ INFO] [1711466745.051765050]: Plugin mag_calibration_status initialized
[ INFO] [1711466745.051880301]: Plugin manual_control loaded
[ INFO] [1711466745.053143254]: Plugin manual_control initialized
[ INFO] [1711466745.053251516]: Plugin mocap_pose_estimate loaded
[ INFO] [1711466745.054997432]: Plugin mocap_pose_estimate initialized
[ INFO] [1711466745.055097429]: Plugin mount_control loaded
[ WARN] [1711466745.057690898]: Could not retrive negate_measured_roll parameter value, using default (0)
[ WARN] [1711466745.057881050]: Could not retrive negate_measured_pitch parameter value, using default (0)
[ WARN] [1711466745.058077089]: Could not retrive negate_measured_yaw parameter value, using default (0)
[ WARN] [1711466745.058878951]: Could not retrive debounce_s parameter value, using default (4.000000)
[ WARN] [1711466745.059140390]: Could not retrive err_threshold_deg parameter value, using default (10.000000)
[ INFO] [1711466745.059204307]: Plugin mount_control initialized
[ INFO] [1711466745.059297155]: Plugin nav_controller_output loaded
[ INFO] [1711466745.059661132]: Plugin nav_controller_output initialized
[ INFO] [1711466745.059736525]: Plugin obstacle_distance loaded
[ INFO] [1711466745.061485911]: Plugin obstacle_distance initialized
[ INFO] [1711466745.061579829]: Plugin odom loaded
[ INFO] [1711466745.063224262]: Plugin odom initialized
[ INFO] [1711466745.063313981]: Plugin onboard_computer_status loaded
[ INFO] [1711466745.064540743]: Plugin onboard_computer_status initialized
[ INFO] [1711466745.064688827]: Plugin param loaded
[ INFO] [1711466745.066229264]: Plugin param initialized
[ INFO] [1711466745.066333725]: Plugin play_tune loaded
[ INFO] [1711466745.067365770]: Plugin play_tune initialized
[ INFO] [1711466745.067402955]: Plugin px4flow blacklisted
[ INFO] [1711466745.067483188]: Plugin rallypoint loaded
[ INFO] [1711466745.068708724]: Plugin rallypoint initialized
[ INFO] [1711466745.068796690]: Plugin rangefinder loaded
[ INFO] [1711466745.069074859]: Plugin rangefinder initialized
[ INFO] [1711466745.069178396]: Plugin rc_io loaded
[ INFO] [1711466745.070803038]: Plugin rc_io initialized
[ INFO] [1711466745.070820427]: Plugin safety_area blacklisted
[ INFO] [1711466745.070912896]: Plugin setpoint_accel loaded
[ INFO] [1711466745.072181150]: Plugin setpoint_accel initialized
[ INFO] [1711466745.072341808]: Plugin setpoint_attitude loaded
[ INFO] [1711466745.076894606]: Plugin setpoint_attitude initialized
[ INFO] [1711466745.077006207]: Plugin setpoint_position loaded
[ INFO] [1711466745.083446556]: Plugin setpoint_position initialized
[ INFO] [1711466745.083572323]: Plugin setpoint_raw loaded
[ INFO] [1711466745.088108545]: Plugin setpoint_raw initialized
[ INFO] [1711466745.088203560]: Plugin setpoint_trajectory loaded
[ INFO] [1711466745.090791069]: Plugin setpoint_trajectory initialized
[ INFO] [1711466745.090926778]: Plugin setpoint_velocity loaded
[ INFO] [1711466745.093280355]: Plugin setpoint_velocity initialized
[ INFO] [1711466745.093540504]: Plugin sys_status loaded
[ INFO] [1711466745.098792472]: Plugin sys_status initialized
[ INFO] [1711466745.098917072]: Plugin sys_time loaded
[ INFO] [1711466745.101234592]: TM: Timesync mode: MAVLINK
[ INFO] [1711466745.101421696]: TM: Not publishing sim time
[ INFO] [1711466745.101939736]: Plugin sys_time initialized
[ INFO] [1711466745.102066094]: Plugin terrain loaded
[ INFO] [1711466745.102415041]: Plugin terrain initialized
[ INFO] [1711466745.102512640]: Plugin trajectory loaded
[ INFO] [1711466745.104770492]: Plugin trajectory initialized
[ INFO] [1711466745.104843052]: Plugin tunnel loaded
[ INFO] [1711466745.106104865]: Plugin tunnel initialized
[ INFO] [1711466745.106225977]: Plugin vfr_hud loaded
[ INFO] [1711466745.106527988]: Plugin vfr_hud initialized
[ INFO] [1711466745.106543195]: Plugin vibration blacklisted
[ INFO] [1711466745.106610831]: Plugin vision_pose_estimate loaded
[ INFO] [1711466745.109754809]: Plugin vision_pose_estimate initialized
[ INFO] [1711466745.109769466]: Plugin vision_speed_estimate blacklisted
[ INFO] [1711466745.109885243]: Plugin waypoint loaded
[ INFO] [1711466745.112175073]: Plugin waypoint initialized
[ INFO] [1711466745.112192068]: Plugin wheel_odometry blacklisted
[ INFO] [1711466745.112268221]: Plugin wind_estimation loaded
[ INFO] [1711466745.112561129]: Plugin wind_estimation initialized
[ INFO] [1711466745.112763316]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1711466745.112800590]: Built-in MAVLink package version: 2024.3.3
[ INFO] [1711466745.112811403]: Known MAVLink dialects: common ardupilotmega ASLUAV AVSSUAS all csAirLink cubepilot development icarous matrixpilot paparazzi standard storm32 uAvionix ualberta
[ INFO] [1711466745.112823848]: MAVROS started. MY ID 1.240, TARGET ID 1.1
[ WARN] [1711466747.090938941]: TM : RTT too high for timesync: 88.85 ms.
[ INFO] [1711466747.174847995]: CON: Got HEARTBEAT, connected. FCU: ArduPilot
[ WARN] [1711466748.182805739]: CMD: Unexpected command 520, result 0
[ INFO] [1711466748.185624145]: GF: Using MISSION_ITEM_INT
[ INFO] [1711466748.185661359]: RP: Using MISSION_ITEM_INT
[ INFO] [1711466748.185703592]: WP: Using MISSION_ITEM_INT
[ INFO] [1711466748.185762050]: VER: 1.1: Capabilities         0x000000000000fbef
[ INFO] [1711466748.185774099]: VER: 1.1: Flight software:     040404ff (db53a28f)
[ INFO] [1711466748.185798242]: VER: 1.1: Middleware software: 00000000 (        )
[ INFO] [1711466748.185819454]: VER: 1.1: OS software:         00000000 (17a50e3a	AW?)
[ INFO] [1711466748.185856033]: VER: 1.1: Board hardware:      00090000
[ INFO] [1711466748.185870136]: VER: 1.1: VID/PID:             1209:5741
[ INFO] [1711466748.185904884]: VER: 1.1: UID:                 0000000000000000
[ INFO] [1711466748.892139778]: FCU: Calibrating barometer
[ INFO] [1711466749.619964501]: FCU: Initialising ArduPilot
[ INFO] [1711466750.504894863]: FCU: Barometer 1 calibration complete
[ INFO] [1711466751.556917471]: FCU: ArduPilot Ready
[ INFO] [1711466751.556971768]: FCU: AHRS: DCM active
[ INFO] [1711466751.558906313]: FCU: RCOut: OS125:1-8 PWM:9-14
[ INFO] [1711466753.562872930]: FCU: EKF3 IMU0 initialised
[ INFO] [1711466753.562951556]: FCU: EKF3 IMU1 initialised
[ INFO] [1711466753.563073127]: FCU: AHRS: EKF3 active
[ INFO] [1711466754.682345184]: FCU: EKF3 IMU0 tilt alignment complete
[ INFO] [1711466754.684305065]: FCU: EKF3 IMU1 tilt alignment complete
[ INFO] [1711466757.175516439]: HP: requesting home position
[ INFO] [1711466757.180612653]: FCU: ArduCopter V4.4.4 (db53a28f)
[ INFO] [1711466757.180840003]: FCU: ChibiOS: 17a50e3a
[ INFO] [1711466757.181436871]: FCU: fmuv3 00460041 33375113 31313537
[ INFO] [1711466757.183006564]: FCU: RCOut: OS125:1-8 PWM:9-14
[ INFO] [1711466757.183247285]: FCU: IMU0: fast sampling enabled 8.0kHz/1.0kHz
[ INFO] [1711466757.183571715]: FCU: Frame: QUAD/X
[ INFO] [1711466762.176819499]: GF: mission received
[ INFO] [1711466762.178662025]: RP: mission received
[ INFO] [1711466762.179708872]: WP: mission received
[ INFO] [1711466767.175731296]: HP: requesting home position
[ERROR] [1711466775.556004147]: FCU: PreArm: Hardware safety switch
[ERROR] [1711466775.556068040]: FCU: PreArm: VisOdom: not healthy
[ INFO] [1711466777.175453066]: HP: requesting home position
[ INFO] [1711466780.789185220]: PR: parameters list received
[ INFO] [1711466781.998806847]: FCU: EKF3 IMU0 yaw aligned
[ INFO] [1711466781.999871194]: FCU: EKF3 IMU0 is using external nav data
[ INFO] [1711466782.001922814]: FCU: EKF3 IMU0 initial pos NED = -0.0,-1.2,-0.1 (m)
[ INFO] [1711466782.003756645]: FCU: EKF3 IMU1 yaw aligned
[ INFO] [1711466782.004908533]: FCU: EKF3 IMU1 is using external nav data
[ INFO] [1711466782.005734052]: FCU: EKF3 IMU1 initial pos NED = -0.0,-1.2,-0.1 (m)
[ INFO] [1711466787.175511054]: HP: requesting home position
[ INFO] [1711466789.240493799]: FCU: EKF3 IMU0 origin set
[ INFO] [1711466789.241415175]: FCU: EKF3 IMU1 origin set
[ INFO] [1711466789.256440100]: FCU: Field Elevation Set: 163m
[ERROR] [1711466805.555454115]: FCU: PreArm: Hardware safety switch
  1. when Mission planner is connected using TCP then GP: No GPS Fix warning pops up. data is published on /mavros/local_position/pose
[ERROR] [1711466835.555700882]: FCU: PreArm: Hardware safety switch
[ERROR] [1711466865.557268715]: FCU: PreArm: Hardware safety switch
[ERROR] [1711466895.555161383]: FCU: PreArm: Hardware safety switch
[ERROR] [1711466926.553762634]: FCU: PreArm: Hardware safety switch
[ERROR] [1711466957.551174356]: FCU: PreArm: Hardware safety switch
[ERROR] [1711466988.550928593]: FCU: PreArm: Hardware safety switch
[ INFO] [1711467002.661648255]: tcp1: Got client, id: 2, address: 192.168.88.110:49417
[ INFO] [1711467003.684425225]: RC_CHANNELS message detected!
[ INFO] [1711467003.684601227]: IMU: Raw IMU message used.
[ WARN] [1711467003.687363532]: GP: No GPS fix
[ WARN] [1711467003.688325170]: TM: Wrong FCU time.
[ WARN] [1711467005.588315273]: CMD: Unexpected command 512, result 0
[ INFO] [1711467005.589326331]: VER: 1.1: Capabilities         0x000000000000fbef
[ INFO] [1711467005.589343748]: VER: 1.1: Flight software:     040404ff (db53a28f)
[ INFO] [1711467005.589357613]: VER: 1.1: Middleware software: 00000000 (        )
[ INFO] [1711467005.589397251]: VER: 1.1: OS software:         00000000 (17a50e3a	AW?)
[ INFO] [1711467005.589413454]: VER: 1.1: Board hardware:      00090000
[ INFO] [1711467005.589427031]: VER: 1.1: VID/PID:             1209:5741
[ INFO] [1711467005.589435099]: VER: 1.1: UID:                 0000000000000000
[ INFO] [1711467005.594343742]: VER: 1.1: Capabilities         0x000000000000fbef
[ INFO] [1711467005.594361977]: VER: 1.1: Flight software:     040404ff (db53a28f)
[ INFO] [1711467005.594371143]: VER: 1.1: Middleware software: 00000000 (        )
[ INFO] [1711467005.594406998]: VER: 1.1: OS software:         00000000 (17a50e3a	AW?)
[ INFO] [1711467005.594420004]: VER: 1.1: Board hardware:      00090000
[ INFO] [1711467005.594434951]: VER: 1.1: VID/PID:             1209:5741
[ INFO] [1711467005.594468762]: VER: 1.1: UID:                 0000000000000000
[ INFO] [1711467005.700180212]: FCU: ArduCopter V4.4.4 (db53a28f)
[ INFO] [1711467005.702185333]: FCU: ChibiOS: 17a50e3a
[ INFO] [1711467005.702272320]: FCU: fmuv3 00460041 33375113 31313537
[ INFO] [1711467005.702322104]: FCU: RCOut: OS125:1-8 PWM:9-14
[ INFO] [1711467005.704192444]: FCU: IMU0: fast sampling enabled 8.0kHz/1.0kHz
[ INFO] [1711467005.704282137]: FCU: Frame: QUAD/X
[ INFO] [1711467006.049989687]: FCU: ArduCopter V4.4.4 (db53a28f)
[ INFO] [1711467006.050346857]: FCU: ChibiOS: 17a50e3a
[ INFO] [1711467006.050945401]: FCU: fmuv3 00460041 33375113 31313537
[ INFO] [1711467006.051307615]: FCU: RCOut: OS125:1-8 PWM:9-14
[ INFO] [1711467006.051950354]: FCU: IMU0: fast sampling enabled 8.0kHz/1.0kHz
[ INFO] [1711467006.052229905]: FCU: Frame: QUAD/X
[ INFO] [1711467006.168708162]: FCU: ArduCopter V4.4.4 (db53a28f)
[ INFO] [1711467006.168810385]: FCU: ChibiOS: 17a50e3a
[ INFO] [1711467006.169697607]: FCU: fmuv3 00460041 33375113 31313537
[ INFO] [1711467006.170654716]: FCU: RCOut: OS125:1-8 PWM:9-14
[ INFO] [1711467006.171715898]: FCU: IMU0: fast sampling enabled 8.0kHz/1.0kHz
[ INFO] [1711467006.171776179]: FCU: Frame: QUAD/X
[ERROR] [1711467018.549174982]: FCU: PreArm: Hardware safety switch

Could anyone please help me the with the issue ? that why there is no data in /mavros/local_position/pose when apm.launch launch file is excuted. Finally ROS will be running on RPI 4B and connected to pixhawk, and mission planner will not be used, instead i want to send the setpoint and drone modes and control it via MAVROS alone.