mavros icon indicating copy to clipboard operation
mavros copied to clipboard

Can arm in stabilized mode but cannot arm in offboard mode.

Open LishuoPan opened this issue 1 year ago • 1 comments

This is only bug and feature tracker, please use it to report bugs or request features.


Issue details

Please describe the problem, or desired feature

  • I can arm the drone when in stabilized mode and can manually fly with a RC. However, I tried to use the script to hover in offboard mode. It can enter the offboard mode, but cannot arm.
  • I use the mocap as the /mavros/vision_pose/pose node and enabled the external vision in EFK2. I have checked the /mavros/local_position/pose and that is correct.
  • I use "rosrun mavros mavsafety arm", before entering the offboard mode and motor spins. But once in offboard mode, when I run that command again, it gives me "Request failed. Check mavros logs". header: seq: 400 stamp: secs: 1733192715 nsecs: 872899236 frame_id: '' status:

    level: 0 name: "mavros: FCU connection" message: "connected" hardware_id: "/dev/ttyACM0:57600" values: - key: "Received packets:" value: "877" - key: "Dropped packets:" value: "0" - key: "Buffer overruns:" value: "0" - key: "Parse errors:" value: "0" - key: "Rx sequence number:" value: "60" - key: "Tx sequence number:" value: "0" - key: "Rx total bytes:" value: "12170209" - key: "Tx total bytes:" value: "331575" - key: "Rx speed:" value: "32498.000000" - key: "Tx speed:" value: "854.000000"

    level: 2 name: "mavros: GPS" message: "No satellites" hardware_id: "/dev/ttyACM0:57600" 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: "/dev/ttyACM0:57600" values: - key: "Mode" value: "255"

    level: 0 name: "mavros: Heartbeat" message: "Normal" hardware_id: "/dev/ttyACM0:57600" values: - key: "Heartbeats since startup" value: "565" - key: "Frequency (Hz)" value: "1.000001" - key: "Vehicle type" value: "Quadrotor" - key: "Autopilot type" value: "PX4 Autopilot" - key: "Mode" value: "OFFBOARD" - key: "System status" value: "Uninit"

    level: 2 name: "mavros: System" message: "Sensor health" hardware_id: "/dev/ttyACM0:57600" values: - key: "Sensor present" value: "0x02210009" - key: "Sensor enabled" value: "0x02210009" - key: "Sensor health" value: "0x2301803F" - key: "3D gyro" value: "Ok" - key: "absolute pressure" value: "Ok" - key: "rc receiver" value: "Ok" - key: "AHRS subsystem health" value: "Fail" - key: "Battery" value: "Ok" - key: "CPU Load (%)" value: "56.7" - 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: 1 name: "mavros: Battery" message: "Low voltage" hardware_id: "/dev/ttyACM0:57600" values: - key: "Voltage" value: "7.25" - key: "Current" value: "-6.8" - key: "Remaining" value: "55.0"

    level: 0 name: "mavros: Time Sync" message: "Normal" hardware_id: "/dev/ttyACM0:57600" values: - key: "Timesyncs since startup" value: "5619" - key: "Frequency (Hz)" value: "10.000074" - key: "Last RTT (ms)" value: "1.419962" - key: "Mean RTT (ms)" value: "2.524334" - key: "Last remote time (s)" value: "773.512660000" - key: "Estimated time offset (s)" value: "1733191942.266791105"

  • Here is the log of px4.launch 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: True
  • /mavros/fake_gps/use_vision: False
  • /mavros/fcu_protocol: v2.0
  • /mavros/fcu_url: /dev/ttyACM0:57600
  • /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/map_id_des: map
  • /mavros/odometry/fcu/odom_child_id_des: base_link
  • /mavros/odometry/fcu/odom_parent_id_des: odom
  • /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.17.0

NODES / mavros (mavros/mavros_node)

ROS_MASTER_URI=http://lishuo-ThinkPadP1:11311

process[mavros-1]: started with pid [2615] [ INFO] [1733192784.986028375]: FCU URL: /dev/ttyACM0:57600 [ INFO] [1733192785.004327579]: serial0: device: /dev/ttyACM0 @ 57600 bps [ INFO] [1733192785.005860790]: GCS bridge disabled [ INFO] [1733192785.083890356]: Plugin 3dr_radio loaded [ INFO] [1733192785.112196407]: Plugin 3dr_radio initialized [ INFO] [1733192785.113441523]: Plugin actuator_control loaded [ INFO] [1733192785.144885035]: Plugin actuator_control initialized [ INFO] [1733192785.165580294]: Plugin adsb loaded [ INFO] [1733192785.195647875]: Plugin adsb initialized [ INFO] [1733192785.196364289]: Plugin altitude loaded [ INFO] [1733192785.206139425]: Plugin altitude initialized [ INFO] [1733192785.207288893]: Plugin cam_imu_sync loaded [ INFO] [1733192785.214264422]: Plugin cam_imu_sync initialized [ INFO] [1733192785.215188387]: Plugin camera loaded [ INFO] [1733192785.220716912]: Plugin camera initialized [ INFO] [1733192785.221935916]: Plugin cellular_status loaded [ INFO] [1733192785.250132527]: Plugin cellular_status initialized [ INFO] [1733192785.251597867]: Plugin command loaded [ INFO] [1733192785.324735257]: Plugin command initialized [ INFO] [1733192785.326272628]: Plugin companion_process_status loaded [ INFO] [1733192785.352827964]: Plugin companion_process_status initialized [ INFO] [1733192785.353515258]: Plugin debug_value loaded [ INFO] [1733192785.452890546]: Plugin debug_value initialized [ INFO] [1733192785.453059282]: Plugin distance_sensor blacklisted [ INFO] [1733192785.453817199]: Plugin esc_status loaded [ INFO] [1733192785.464409164]: Plugin esc_status initialized [ INFO] [1733192785.465888903]: Plugin esc_telemetry loaded [ INFO] [1733192785.472559761]: Plugin esc_telemetry initialized [ INFO] [1733192785.474648170]: Plugin fake_gps loaded [ INFO] [1733192785.754630606]: Plugin fake_gps initialized [ INFO] [1733192785.755661003]: Plugin ftp loaded [ INFO] [1733192785.818304604]: Plugin ftp initialized [ INFO] [1733192785.819172761]: Plugin geofence loaded [ INFO] [1733192785.932091941]: Plugin geofence initialized [ INFO] [1733192785.932955490]: Plugin global_position loaded [ INFO] [1733192786.197241724]: Plugin global_position initialized [ INFO] [1733192786.197938426]: Plugin gps_input loaded

MAVROS version and platform

Mavros: 1.20.0 ROS: Noetic Ubuntu: 20.04

Autopilot type and version

[ ] ArduPilot [ - ] PX4

Version: ?3.7.1?

Node logs

copy output of mavros_node. Usually console where you run roslaunch

Diagnostics

place here result of:
rostopic echo -n1 /diagnostics

Check ID

rosrun mavros checkid

LishuoPan avatar Dec 03 '24 02:12 LishuoPan

to arm a px4 based drone in Offboard mode, you need to send a stream of Setpoint commands to the device, predominantly done through mavros, have you done this?

DARKMOONlite avatar Dec 09 '24 03:12 DARKMOONlite