mavlink / mavros

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

Question about sending external pose to mavros #1872

Open prashantganesh-episci opened 1 year ago

prashantganesh-episci commented 1 year ago

Hi, I am following PX4's instructions on sending external vison based pose and it requests sending pose estimates to mavros/vision_pose/pose. What is the difference between sending the pose to that topic vs sending it to /mavros/local_position/pose? Digging into the setpoint_position.cpp it looks like the /mavros/local_position/pose updates the local position: image


Issue details

I also noticed that the setpoint_poisition.cpp subscribes to /mavros/local_position/pose while the local_position.cpp plugin subscribes to the same topic which creates a loop. Is this something that needs to be changed?

image

MAVROS version and platform

Mavros: 1.16.0 ROS: Noetic Ubuntu: 20.04

Autopilot type and version

[ ] ArduPilot [ x ] PX4

Node logs

roslaunch mavros px4.launch fcu_url:="udp://:14540@127.0.0.1:14557"
... logging to /home/prashantganesh@int-episci.com/.ros/log/818f93de-16bc-11ee-ab6e-c550d7443979/roslaunch-ironman-1527182.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.

started roslaunch server http://ironman:43467/

SUMMARY
========

CLEAR PARAMETERS
 * /mavros/

PARAMETERS
 * /mavros/camera/frame_id: base_link
 * /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: 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: False
 * /mavros/fake_gps/use_vision: True
 * /mavros/fcu_protocol: v2.0
 * /mavros/fcu_url: udp://:14540@127....
 * /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/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/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: 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: 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: noetic
 * /rosversion: 1.16.0

NODES
  /
    mavros (mavros/mavros_node)

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

setting /run_id to 818f93de-16bc-11ee-ab6e-c550d7443979
process[rosout-1]: started with pid [1527211]
started core service [/rosout]
process[mavros-2]: started with pid [1527219]
[ INFO] [1688070939.100945591]: FCU URL: udp://:14540@127.0.0.1:14557
[ INFO] [1688070939.107292509]: udp0: Bind address: 0.0.0.0:14540
[ INFO] [1688070939.107464420]: udp0: Remote address: 127.0.0.1:14557
[ INFO] [1688070939.107918685]: GCS bridge disabled
[ INFO] [1688070939.133558349]: Plugin 3dr_radio loaded
[ INFO] [1688070939.136659320]: Plugin 3dr_radio initialized
[ INFO] [1688070939.136830860]: Plugin actuator_control loaded
[ INFO] [1688070939.141857388]: Plugin actuator_control initialized
[ INFO] [1688070939.153305723]: Plugin adsb loaded
[ INFO] [1688070939.158744688]: Plugin adsb initialized
[ INFO] [1688070939.159063689]: Plugin altitude loaded
[ INFO] [1688070939.160786289]: Plugin altitude initialized
[ INFO] [1688070939.161023283]: Plugin cam_imu_sync loaded
[ INFO] [1688070939.162323650]: Plugin cam_imu_sync initialized
[ INFO] [1688070939.162596732]: Plugin camera loaded
[ INFO] [1688070939.163709655]: Plugin camera initialized
[ INFO] [1688070939.163943652]: Plugin cellular_status loaded
[ INFO] [1688070939.167875518]: Plugin cellular_status initialized
[ INFO] [1688070939.168227484]: Plugin command loaded
[ INFO] [1688070939.180976591]: Plugin command initialized
[ INFO] [1688070939.181270853]: Plugin companion_process_status loaded
[ INFO] [1688070939.185486281]: Plugin companion_process_status initialized
[ INFO] [1688070939.185828542]: Plugin debug_value loaded
[ INFO] [1688070939.194953216]: Plugin debug_value initialized
[ INFO] [1688070939.195019540]: Plugin distance_sensor blacklisted
[ INFO] [1688070939.195345186]: Plugin esc_status loaded
[ INFO] [1688070939.197491063]: Plugin esc_status initialized
[ INFO] [1688070939.197806776]: Plugin esc_telemetry loaded
[ INFO] [1688070939.199159930]: Plugin esc_telemetry initialized
[ INFO] [1688070939.199511160]: Plugin fake_gps loaded
[ INFO] [1688070939.223873222]: Plugin fake_gps initialized
[ INFO] [1688070939.224289876]: Plugin ftp loaded
[ INFO] [1688070939.237505367]: Plugin ftp initialized
[ INFO] [1688070939.237901820]: Plugin geofence loaded
[ INFO] [1688070939.244544409]: Plugin geofence initialized
[ INFO] [1688070939.244916474]: Plugin global_position loaded
[ INFO] [1688070939.272535167]: Plugin global_position initialized
[ INFO] [1688070939.272887824]: Plugin gps_input loaded
[ INFO] [1688070939.279053517]: Plugin gps_input initialized
[ INFO] [1688070939.279424658]: Plugin gps_rtk loaded
[ INFO] [1688070939.284517575]: Plugin gps_rtk initialized
[ INFO] [1688070939.284841486]: Plugin gps_status loaded
[ INFO] [1688070939.289049038]: Plugin gps_status initialized
[ INFO] [1688070939.289397563]: Plugin guided_target loaded
[ INFO] [1688070939.296674424]: Plugin guided_target initialized
[ INFO] [1688070939.297087867]: Plugin hil loaded
[ INFO] [1688070939.318805242]: Plugin hil initialized
[ INFO] [1688070939.319199998]: Plugin home_position loaded
[ INFO] [1688070939.325546083]: Plugin home_position initialized
[ INFO] [1688070939.326083897]: Plugin imu loaded
[ INFO] [1688070939.339276753]: Plugin imu initialized
[ INFO] [1688070939.339630671]: Plugin landing_target loaded
[ INFO] [1688070939.362502714]: Plugin landing_target initialized
[ INFO] [1688070939.362896900]: Plugin local_position loaded
[ INFO] [1688070939.371851617]: Plugin local_position initialized
[ INFO] [1688070939.372201018]: Plugin log_transfer loaded
[ INFO] [1688070939.378701916]: Plugin log_transfer initialized
[ INFO] [1688070939.379040779]: Plugin mag_calibration_status loaded
[ INFO] [1688070939.381252749]: Plugin mag_calibration_status initialized
[ INFO] [1688070939.381628008]: Plugin manual_control loaded
[ INFO] [1688070939.386708115]: Plugin manual_control initialized
[ INFO] [1688070939.387049627]: Plugin mocap_pose_estimate loaded
[ INFO] [1688070939.393194795]: Plugin mocap_pose_estimate initialized
[ INFO] [1688070939.393547649]: Plugin mount_control loaded
[ WARN] [1688070939.403072102]: Could not retrive negate_measured_roll parameter value, using default (0)
[ WARN] [1688070939.403771403]: Could not retrive negate_measured_pitch parameter value, using default (0)
[ WARN] [1688070939.404440633]: Could not retrive negate_measured_yaw parameter value, using default (0)
[ WARN] [1688070939.406907298]: Could not retrive debounce_s parameter value, using default (4.000000)
[ WARN] [1688070939.407581694]: Could not retrive err_threshold_deg parameter value, using default (10.000000)
[ INFO] [1688070939.407745017]: Plugin mount_control initialized
[ INFO] [1688070939.408116255]: Plugin nav_controller_output loaded
[ INFO] [1688070939.409283980]: Plugin nav_controller_output initialized
[ INFO] [1688070939.409846576]: Plugin obstacle_distance loaded
[ INFO] [1688070939.414713501]: Plugin obstacle_distance initialized
[ INFO] [1688070939.415048527]: Plugin odom loaded
[ INFO] [1688070939.422482660]: Plugin odom initialized
[ INFO] [1688070939.422824945]: Plugin onboard_computer_status loaded
[ INFO] [1688070939.426915421]: Plugin onboard_computer_status initialized
[ INFO] [1688070939.427347461]: Plugin param loaded
[ INFO] [1688070939.433047336]: Plugin param initialized
[ INFO] [1688070939.433732211]: Plugin play_tune loaded
[ INFO] [1688070939.437951033]: Plugin play_tune initialized
[ INFO] [1688070939.438244693]: Plugin px4flow loaded
[ INFO] [1688070939.449654480]: Plugin px4flow initialized
[ INFO] [1688070939.450064485]: Plugin rallypoint loaded
[ INFO] [1688070939.455221479]: Plugin rallypoint initialized
[ INFO] [1688070939.455293264]: Plugin rangefinder blacklisted
[ INFO] [1688070939.455723308]: Plugin rc_io loaded
[ INFO] [1688070939.462116619]: Plugin rc_io initialized
[ INFO] [1688070939.462190494]: Plugin safety_area blacklisted
[ INFO] [1688070939.462524718]: Plugin setpoint_accel loaded
[ INFO] [1688070939.467684914]: Plugin setpoint_accel initialized
[ INFO] [1688070939.468166170]: Plugin setpoint_attitude loaded
[ INFO] [1688070939.485988079]: Plugin setpoint_attitude initialized
[ INFO] [1688070939.486384175]: Plugin setpoint_position loaded
[ INFO] [1688070939.512013903]: Plugin setpoint_position initialized
[ INFO] [1688070939.512393344]: Plugin setpoint_raw loaded
[ INFO] [1688070939.528017405]: Plugin setpoint_raw initialized
[ INFO] [1688070939.528377331]: Plugin setpoint_trajectory loaded
[ INFO] [1688070939.536460676]: Plugin setpoint_trajectory initialized
[ INFO] [1688070939.536824525]: Plugin setpoint_velocity loaded
[ INFO] [1688070939.546208441]: Plugin setpoint_velocity initialized
[ INFO] [1688070939.546884038]: Plugin sys_status loaded
[ INFO] [1688070939.566167256]: Plugin sys_status initialized
[ INFO] [1688070939.566609288]: Plugin sys_time loaded
[ INFO] [1688070939.575461145]: TM: Timesync mode: MAVLINK
[ INFO] [1688070939.576096432]: TM: Not publishing sim time
[ INFO] [1688070939.578190684]: Plugin sys_time initialized
[ INFO] [1688070939.578512289]: Plugin terrain loaded
[ INFO] [1688070939.579733601]: Plugin terrain initialized
[ INFO] [1688070939.580016251]: Plugin trajectory loaded
[ INFO] [1688070939.589476553]: Plugin trajectory initialized
[ INFO] [1688070939.589828096]: Plugin tunnel loaded
[ INFO] [1688070939.595586161]: Plugin tunnel initialized
[ INFO] [1688070939.595961323]: Plugin vfr_hud loaded
[ INFO] [1688070939.597180892]: Plugin vfr_hud initialized
[ INFO] [1688070939.597250487]: Plugin vibration blacklisted
[ INFO] [1688070939.597796100]: Plugin vision_pose_estimate loaded
[ INFO] [1688070939.611232754]: Plugin vision_pose_estimate initialized
[ INFO] [1688070939.611596860]: Plugin vision_speed_estimate loaded
[ INFO] [1688070939.618306278]: Plugin vision_speed_estimate initialized
[ INFO] [1688070939.618832460]: Plugin waypoint loaded
[ INFO] [1688070939.627567462]: Plugin waypoint initialized
[ INFO] [1688070939.627650229]: Plugin wheel_odometry blacklisted
[ INFO] [1688070939.628107173]: Plugin wind_estimation loaded
[ INFO] [1688070939.629574324]: Plugin wind_estimation initialized
[ INFO] [1688070939.630121614]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1688070939.630215205]: Built-in MAVLink package version: 2023.6.6
[ INFO] [1688070939.630316920]: Known MAVLink dialects: common ardupilotmega ASLUAV AVSSUAS all csAirLink cubepilot development icarous matrixpilot paparazzi standard storm32 uAvionix ualberta
[ INFO] [1688070939.630420271]: MAVROS started. MY ID 1.240, TARGET ID 1.1

Diagnostics

rostopic echo -n1 /diagnostics
header: 
  seq: 9
  stamp: 
    secs: 1688072829
    nsecs: 498342588
  frame_id: ''
status: 
  - 
    level: 1
    name: "mavros: FCU connection"
    message: "not connected"
    hardware_id: "udp://:14540@127.0.0.1:14557"
    values: 
      - 
        key: "Received packets:"
        value: "0"
      - 
        key: "Dropped packets:"
        value: "0"
      - 
        key: "Buffer overruns:"
        value: "0"
      - 
        key: "Parse errors:"
        value: "0"
      - 
        key: "Rx sequence number:"
        value: "0"
      - 
        key: "Tx sequence number:"
        value: "0"
      - 
        key: "Rx total bytes:"
        value: "0"
      - 
        key: "Tx total bytes:"
        value: "1100"
      - 
        key: "Rx speed:"
        value: "0.000000"
      - 
        key: "Tx speed:"
        value: "460.000000"
  - 
    level: 2
    name: "mavros: GPS"
    message: "No satellites"
    hardware_id: "udp://:14540@127.0.0.1:14557"
    values: 
      - 
        key: "Satellites visible"
        value: "0"
      - 
        key: "Fix type"
        value: "0"
      - 
        key: "EPH (m)"
        value: "Unknown"
      - 
        key: "EPV (m)"
        value: "Unknown"
  - 
    level: 1
    name: "mavros: Mount"
    message: "Can not diagnose in this targeting mode"
    hardware_id: "udp://:14540@127.0.0.1:14557"
    values: 
      - 
        key: "Mode"
        value: "255"
  - 
    level: 2
    name: "mavros: Heartbeat"
    message: "No events recorded."
    hardware_id: "udp://:14540@127.0.0.1:14557"
    values: 
      - 
        key: "Heartbeats since startup"
        value: "0"
      - 
        key: "Frequency (Hz)"
        value: "0.000000"
      - 
        key: "Vehicle type"
        value: "Generic micro air vehicle"
      - 
        key: "Autopilot type"
        value: "Generic autopilot"
      - 
        key: "Mode"
        value: ''
      - 
        key: "System status"
        value: "Uninit"
  - 
    level: 0
    name: "mavros: System"
    message: "Normal"
    hardware_id: "udp://:14540@127.0.0.1:14557"
    values: 
      - 
        key: "Sensor present"
        value: "0x00000000"
      - 
        key: "Sensor enabled"
        value: "0x00000000"
      - 
        key: "Sensor health"
        value: "0x00000000"
      - 
        key: "CPU Load (%)"
        value: "0.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: 2
    name: "mavros: Battery"
    message: "No data"
    hardware_id: "udp://:14540@127.0.0.1:14557"
    values: 
      - 
        key: "Voltage"
        value: "-1.00"
      - 
        key: "Current"
        value: "0.0"
      - 
        key: "Remaining"
        value: "0.0"
  - 
    level: 2
    name: "mavros: Time Sync"
    message: "No events recorded."
    hardware_id: "udp://:14540@127.0.0.1:14557"
    values: 
      - 
        key: "Timesyncs since startup"
        value: "0"
      - 
        key: "Frequency (Hz)"
        value: "0.000000"
      - 
        key: "Last RTT (ms)"
        value: "0.000000"
      - 
        key: "Mean RTT (ms)"
        value: "0.000000"
      - 
        key: "Last remote time (s)"
        value: "0.000000000"
      - 
        key: "Estimated time offset (s)"
        value: "0.000000000"
---
Kian-Wee commented 1 year ago

If Im not mistakened the /mavros/local_position/pose topic is only for subscribing to the UAV's local position after it runs through the UAV's internal ekf loop, which is what setpoint_position uses to check if its at the desired location. If you want to send in an external pose estimate you need to use the /mavros/vision_pose/pose topic which is an PRE ekf estimation.

vooon commented 1 year ago

One plugin can subscribe to other plugin. That's fine. But on graph you'll see that mavros both publishes and subscribes some topics.

On your diagnostics there no connection, so you'll never get any response from the FCU.

prashantganesh-episci commented 1 year ago

@Kian-Wee and @vooon sounds good. I will try publishing to the /vision_pose/pose topic. Thank you!

Inhan1998 commented 1 year ago

@Kian-Wee @vooon We publish the /vision_pose/pose topic, but /mavros/local_position/pose is not affected. We set EKF2_AID_MASK to 280 and SYS_MC_EST_GROUP to 1(ekf2). and We are using melodic.

Inhan1998 commented 1 year ago

Should I change these params?

vooon commented 1 year ago

No, i think you probably need to change something in FC's params.

Inhan1998 commented 1 year ago

No, i think you probably need to change something in FC's params.

@vooon Could you tell me more detail about that? What's the FC's params?

Inhan1998 commented 1 year ago

I can't find those params in my qgc image

Kian-Wee commented 1 year ago

I can't find those params in my qgc image

Those params are for LPE, Not EKF2

What rate are you sending in your vision_pose at? It should be minimally 30hz(with covariance). You should be able to verify if the FC is receiving it by typing listener vehicle_visual_odometry into the mavlink console in QGC if you enable the GCS bridge.