MAVLink + PX4 communicating with base station for computations

Hi,

I have some code that works with PX4 + Gazebo and I am trying to setup my physical tests with a MoCap system. I think everything is configured properly, except for how to communicate from my quadcopter to my base station. I have a Pixhawk 4 Mini with a Raspberry Pi Zero W connected on Telem1 at 115200 BAUD. I want to forward the information from the Pixhawk to my base station using the wireless capabilities of the Pi Zero. My question is: is it possible to do all of my ROS computation on my base station and merely use the Pi Zero as a proxy ? In this case, would the base station be where I run roslaunch mavros px4.launch? Or do I have to do this on my Pi Zero?

Here is what I have tried so far:

  1. I first tried using Xbee S2C modules, these worked a bit at 57600 BAUD, but I kept losing and regaining the Heartbeat signal. I tried to bump the BAUD up to 115200, but the MAVLink connection message hangs (when running roslaunch mavros px4.launch). I took this as a sign that the Xbee modules could not handle the message rate so I moved on to the Pi Zero.

  2. With the Maverick image I was able to run roslaunch mavros px4.launch on my Pi Zero with a serial connection to Telem1 via /dev/ttyAMA0. I could see IMU data on the topics here. However, I could not get reliable 2-way communication with my base station. The Pi Zero could communicate with the base station but not vice versa. I think that there is an issue with the built-in firewall here, but it is so slow to re-run maverick configure that its not a desirable development environment. Also, I would much prefer not having to run roslaunch mavros px4.launch on the Pi Zero, and instead do everything from my base station.

  3. I tried installing mavlink-router on a clean raspbian image. I can open a TCP connection on the Pi Zero with my base station, however my base station hangs when running roslaunch mavros px4.launch and the Pi Zero states UART incomplete messages issue!. I have checked the BAUD rates, and they do match up.

One of the main problems here is that I do not know which of these approaches are actually possible (if any). I have been digging around the forums for about 3 weeks now and I still don’t see the way forward. For some context, the end goal here is to manage multiple quadcopters from my base station using some threaded ROS code I developed.

Any feedback would be greatly appreciated!

-Pat

I figured I should at least post an update and see if someone wanted to engage, or has the same issue. By the way, I’m using the most recent master (1.9.0dev) build, I think I forgot to mention this earlier.

I has a BAUD mismatch with the Xbees so I fixed that and I can wirelessly get a reliable heartbeat at 115200 BAUD. From there I can feed MoCap data to my vehicle on the “mavros/vision_pose/pose” topic. I set the “EKF2_AID_MASK” to 24 and “EKF2_HGT_MODE” to 3 (vision). I can query the rostopics “mavros/vision_pose/pose”, “mavros/state”, and “mavros/imu/data” just fine. However, there are a few concerning things going on. In “/diagnostics” the “AHRS subsystem health” is “fail”. Also I cannot echo the rostopics: mavros/imu/data_raw or mavros/local_position/pose. This makes me believe that I don’t have a position lock. Additionally, I am able to use my RC controller to switch into “Position” mode, but the motors just idle (again, I think its the position lock issue). Also the output from “px4.launch” is "HP: requesting home position" repeatedly. I’m not sure what the issue is here and I would really appreciate some outside input as I am working alone.

Below I have put the outputs from px4.launch, rostopic list, /diagnostics, and an image of my “rqt_graph”

started roslaunch server http://odysseus:46483/

SUMMARY

CLEAR PARAMETERS

  • /uav1/mavros/

PARAMETERS

  • /mocap_node/rigid_bodies/1/frame_id: uav/base_link
  • /mocap_node/rigid_bodies/1/pose2d: uav/ground_pose
  • /mocap_node/rigid_bodies/1/pose: uav/pose
  • /rosdistro: kinetic
  • /rosversion: 1.12.14
  • /uav1/mavros/cmd/use_comp_id_system_control: False
  • /uav1/mavros/conn/heartbeat_rate: 1.0
  • /uav1/mavros/conn/system_time_rate: 1.0
  • /uav1/mavros/conn/timeout: 10.0
  • /uav1/mavros/conn/timesync_rate: 0.0
  • /uav1/mavros/distance_sensor/hrlv_ez4_pub/field_of_view: 0.0
  • /uav1/mavros/distance_sensor/hrlv_ez4_pub/frame_id: hrlv_ez4_sonar
  • /uav1/mavros/distance_sensor/hrlv_ez4_pub/id: 0
  • /uav1/mavros/distance_sensor/hrlv_ez4_pub/orientation: PITCH_270
  • /uav1/mavros/distance_sensor/hrlv_ez4_pub/send_tf: True
  • /uav1/mavros/distance_sensor/hrlv_ez4_pub/sensor_position/x: 0.0
  • /uav1/mavros/distance_sensor/hrlv_ez4_pub/sensor_position/y: 0.0
  • /uav1/mavros/distance_sensor/hrlv_ez4_pub/sensor_position/z: -0.1
  • /uav1/mavros/distance_sensor/laser_1_sub/id: 3
  • /uav1/mavros/distance_sensor/laser_1_sub/orientation: PITCH_270
  • /uav1/mavros/distance_sensor/laser_1_sub/subscriber: True
  • /uav1/mavros/distance_sensor/lidarlite_pub/field_of_view: 0.0
  • /uav1/mavros/distance_sensor/lidarlite_pub/frame_id: lidarlite_laser
  • /uav1/mavros/distance_sensor/lidarlite_pub/id: 1
  • /uav1/mavros/distance_sensor/lidarlite_pub/orientation: PITCH_270
  • /uav1/mavros/distance_sensor/lidarlite_pub/send_tf: True
  • /uav1/mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0
  • /uav1/mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0
  • /uav1/mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1
  • /uav1/mavros/distance_sensor/sonar_1_sub/id: 2
  • /uav1/mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270
  • /uav1/mavros/distance_sensor/sonar_1_sub/subscriber: True
  • /uav1/mavros/fake_gps/eph: 2.0
  • /uav1/mavros/fake_gps/epv: 2.0
  • /uav1/mavros/fake_gps/fix_type: 3
  • /uav1/mavros/fake_gps/geo_origin/alt: 408.0
  • /uav1/mavros/fake_gps/geo_origin/lat: 47.3667
  • /uav1/mavros/fake_gps/geo_origin/lon: 8.55
  • /uav1/mavros/fake_gps/gps_rate: 5.0
  • /uav1/mavros/fake_gps/mocap_transform: False
  • /uav1/mavros/fake_gps/satellites_visible: 5
  • /uav1/mavros/fake_gps/tf/child_frame_id: fix
  • /uav1/mavros/fake_gps/tf/frame_id: map
  • /uav1/mavros/fake_gps/tf/listen: False
  • /uav1/mavros/fake_gps/tf/rate_limit: 10.0
  • /uav1/mavros/fake_gps/tf/send: True
  • /uav1/mavros/fake_gps/use_mocap: False
  • /uav1/mavros/fake_gps/use_vision: True
  • /uav1/mavros/fcu_protocol: v2.0
  • /uav1/mavros/fcu_url: /dev/ttyUSB0:115200
  • /uav1/mavros/gcs_url: udp://@localhost:…
  • /uav1/mavros/global_position/child_frame_id: base_link
  • /uav1/mavros/global_position/frame_id: map
  • /uav1/mavros/global_position/gps_uere: 1.0
  • /uav1/mavros/global_position/rot_covariance: 99999.0
  • /uav1/mavros/global_position/tf/child_frame_id: base_link
  • /uav1/mavros/global_position/tf/frame_id: map
  • /uav1/mavros/global_position/tf/global_frame_id: earth
  • /uav1/mavros/global_position/tf/send: False
  • /uav1/mavros/global_position/use_relative_alt: True
  • /uav1/mavros/image/frame_id: px4flow
  • /uav1/mavros/imu/angular_velocity_stdev: 0.000349065850399
  • /uav1/mavros/imu/frame_id: base_link
  • /uav1/mavros/imu/linear_acceleration_stdev: 0.0003
  • /uav1/mavros/imu/magnetic_stdev: 0.0
  • /uav1/mavros/imu/orientation_stdev: 1.0
  • /uav1/mavros/local_position/frame_id: map
  • /uav1/mavros/local_position/tf/child_frame_id: base_link
  • /uav1/mavros/local_position/tf/frame_id: map
  • /uav1/mavros/local_position/tf/send: False
  • /uav1/mavros/local_position/tf/send_fcu: False
  • /uav1/mavros/mission/pull_after_gcs: True
  • /uav1/mavros/mocap/use_pose: True
  • /uav1/mavros/mocap/use_tf: False
  • /uav1/mavros/odometry/in/child_frame_id: base_link
  • /uav1/mavros/odometry/in/frame_id: odom
  • /uav1/mavros/odometry/in/frame_tf/body_frame_orientation: flu
  • /uav1/mavros/odometry/in/frame_tf/local_frame: local_origin_ned
  • /uav1/mavros/odometry/out/frame_tf/body_frame_orientation: frd
  • /uav1/mavros/odometry/out/frame_tf/local_frame: vision_ned
  • /uav1/mavros/plugin_blacklist: [‘safety_area’, '…
  • /uav1/mavros/plugin_whitelist: [‘sys_*’, 'fake_g…
  • /uav1/mavros/px4flow/frame_id: px4flow
  • /uav1/mavros/px4flow/ranger_fov: 0.118682389136
  • /uav1/mavros/px4flow/ranger_max_range: 5.0
  • /uav1/mavros/px4flow/ranger_min_range: 0.3
  • /uav1/mavros/safety_area/p1/x: 1.0
  • /uav1/mavros/safety_area/p1/y: 1.0
  • /uav1/mavros/safety_area/p1/z: 1.0
  • /uav1/mavros/safety_area/p2/x: -1.0
  • /uav1/mavros/safety_area/p2/y: -1.0
  • /uav1/mavros/safety_area/p2/z: -1.0
  • /uav1/mavros/setpoint_accel/send_force: False
  • /uav1/mavros/setpoint_attitude/reverse_thrust: False
  • /uav1/mavros/setpoint_attitude/tf/child_frame_id: target_attitude
  • /uav1/mavros/setpoint_attitude/tf/frame_id: map
  • /uav1/mavros/setpoint_attitude/tf/listen: False
  • /uav1/mavros/setpoint_attitude/tf/rate_limit: 50.0
  • /uav1/mavros/setpoint_attitude/use_quaternion: False
  • /uav1/mavros/setpoint_position/mav_frame: LOCAL_NED
  • /uav1/mavros/setpoint_position/tf/child_frame_id: target_position
  • /uav1/mavros/setpoint_position/tf/frame_id: map
  • /uav1/mavros/setpoint_position/tf/listen: False
  • /uav1/mavros/setpoint_position/tf/rate_limit: 50.0
  • /uav1/mavros/setpoint_raw/thrust_scaling: 1.0
  • /uav1/mavros/setpoint_velocity/mav_frame: LOCAL_NED
  • /uav1/mavros/startup_px4_usb_quirk: True
  • /uav1/mavros/sys/disable_diag: False
  • /uav1/mavros/sys/min_voltage: 10.0
  • /uav1/mavros/target_component_id: 240
  • /uav1/mavros/target_system_id: 1
  • /uav1/mavros/tdr_radio/low_rssi: 40
  • /uav1/mavros/time/time_ref_source: fcu
  • /uav1/mavros/time/timesync_avg_alpha: 0.6
  • /uav1/mavros/time/timesync_mode: MAVLINK
  • /uav1/mavros/vibration/frame_id: base_link
  • /uav1/mavros/vision_pose/tf/child_frame_id: vision_estimate
  • /uav1/mavros/vision_pose/tf/frame_id: map
  • /uav1/mavros/vision_pose/tf/listen: False
  • /uav1/mavros/vision_pose/tf/rate_limit: 30.0
  • /uav1/mavros/vision_speed/listen_twist: True
  • /uav1/mavros/vision_speed/twist_cov: True
  • /uav1/mavros/wheel_odometry/child_frame_id: base_link
  • /uav1/mavros/wheel_odometry/count: 2
  • /uav1/mavros/wheel_odometry/frame_id: map
  • /uav1/mavros/wheel_odometry/send_raw: True
  • /uav1/mavros/wheel_odometry/send_twist: False
  • /uav1/mavros/wheel_odometry/tf/child_frame_id: base_link
  • /uav1/mavros/wheel_odometry/tf/frame_id: map
  • /uav1/mavros/wheel_odometry/tf/send: True
  • /uav1/mavros/wheel_odometry/use_rpm: False
  • /uav1/mavros/wheel_odometry/vel_error: 0.1
  • /uav1/mavros/wheel_odometry/wheel0/radius: 0.05
  • /uav1/mavros/wheel_odometry/wheel0/x: 0.0
  • /uav1/mavros/wheel_odometry/wheel0/y: -0.15
  • /uav1/mavros/wheel_odometry/wheel1/radius: 0.05
  • /uav1/mavros/wheel_odometry/wheel1/x: 0.0
  • /uav1/mavros/wheel_odometry/wheel1/y: 0.15

NODES
/uav1/
mavros (mavros/mavros_node)
/
mocap_node (mocap_optitrack/mocap_node)

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

setting /run_id to b59f996e-5139-11e9-a663-9cb6d0f485cf
process[rosout-1]: started with pid [20594]
started core service [/rosout]
process[uav1/mavros-2]: started with pid [20612]
process[mocap_node-3]: started with pid [20613]
[ INFO] [1553764391.908736519]: FCU URL: /dev/ttyUSB0:115200
[ INFO] [1553764391.910374583]: serial0: device: /dev/ttyUSB0 @ 115200 bps
[ INFO] [1553764392.014270568]: GCS URL: udp://@localhost:14550
[ INFO] [1553764392.014861836]: udp1: Bind address: 0.0.0.0:14555
[ INFO] [1553764392.015028323]: udp1: Remote address: 127.0.0.1:14550
[ INFO] [1553764392.021401777]: Plugin 3dr_radio blacklisted
[ INFO] [1553764392.034935391]: Plugin actuator_control loaded
[ INFO] [1553764392.042133373]: Plugin actuator_control initialized
[ INFO] [1553764392.047802888]: Plugin adsb loaded
[ INFO] [1553764392.055178291]: Plugin adsb initialized
[ INFO] [1553764392.055460188]: Plugin altitude loaded
[ INFO] [1553764392.057657794]: Plugin altitude initialized
[ INFO] [1553764392.057882608]: Plugin cam_imu_sync loaded
[ INFO] [1553764392.059139312]: Plugin cam_imu_sync initialized
[ INFO] [1553764392.059464815]: Plugin command loaded
[ INFO] [1553764392.071932355]: Plugin command initialized
[ INFO] [1553764392.072222771]: Plugin companion_process_status loaded
[ INFO] [1553764392.077373468]: Plugin companion_process_status initialized
[ INFO] [1553764392.077658410]: Plugin debug_value loaded
[ INFO] [1553764392.087497309]: Plugin debug_value initialized
[ INFO] [1553764392.087546030]: Plugin distance_sensor blacklisted
[ INFO] [1553764392.087864676]: Plugin fake_gps loaded
[ INFO] [1553764392.113647236]: Plugin fake_gps initialized
[ INFO] [1553764392.113909180]: Plugin ftp loaded
[ INFO] [1553764392.123580283]: Plugin ftp initialized
[ INFO] [1553764392.123743615]: Plugin global_position loaded
[ INFO] [1553764392.139627899]: Plugin global_position initialized
[ INFO] [1553764392.139758804]: Plugin gps_rtk loaded
[ INFO] [1553764392.142018160]: Plugin gps_rtk initialized
[ INFO] [1553764392.142060304]: Plugin hil blacklisted
[ INFO] [1553764392.142262437]: Plugin home_position loaded
[ INFO] [1553764392.145564788]: Plugin home_position initialized
[ INFO] [1553764392.145728663]: Plugin imu loaded
[ INFO] [1553764392.153543992]: Plugin imu initialized
[ INFO] [1553764392.153750438]: Plugin local_position loaded
[ INFO] [1553764392.159441211]: Plugin local_position initialized
[ INFO] [1553764392.159562258]: Plugin log_transfer loaded
[ INFO] [1553764392.162259251]: Plugin log_transfer initialized
[ INFO] [1553764392.162286903]: Plugin manual_control blacklisted
[ INFO] [1553764392.162405392]: Plugin mocap_pose_estimate loaded
[ INFO] [1553764392.166257840]: Plugin mocap_pose_estimate initialized
[ INFO] [1553764392.166290085]: Plugin obstacle_distance blacklisted
[ INFO] [1553764392.166314871]: Plugin odom blacklisted
[ INFO] [1553764392.166537867]: Plugin param loaded
[ INFO] [1553764392.169279509]: Plugin param initialized
[ INFO] [1553764392.169305660]: Plugin px4flow blacklisted
[ INFO] [1553764392.169327866]: Plugin rangefinder blacklisted
[ INFO] [1553764392.169344562]: Plugin rc_io blacklisted
[ INFO] [1553764392.169362465]: Plugin safety_area blacklisted
[ INFO] [1553764392.169515049]: Plugin setpoint_accel loaded
[ INFO] [1553764392.172660509]: Plugin setpoint_accel initialized
[ INFO] [1553764392.172918172]: Plugin setpoint_attitude loaded
[ INFO] [1553764392.182629666]: Plugin setpoint_attitude initialized
[ INFO] [1553764392.182792460]: Plugin setpoint_position loaded
[ INFO] [1553764392.195678638]: Plugin setpoint_position initialized
[ INFO] [1553764392.195708913]: Plugin setpoint_raw blacklisted
[ INFO] [1553764392.195838698]: Plugin setpoint_velocity loaded
[ INFO] [1553764392.201620516]: Plugin setpoint_velocity initialized
[ INFO] [1553764392.201982066]: Plugin sys_status loaded
[ INFO] [1553764392.211472264]: Plugin sys_status initialized
[ INFO] [1553764392.211630725]: Plugin sys_time loaded
[ INFO] [1553764392.216768556]: TM: Timesync mode: MAVLINK
[ INFO] [1553764392.217953805]: Plugin sys_time initialized
[ INFO] [1553764392.218089772]: Plugin trajectory loaded
[ INFO] [1553764392.222711004]: Plugin trajectory initialized
[ INFO] [1553764392.222733559]: Plugin vfr_hud blacklisted
[ INFO] [1553764392.222749715]: Plugin vibration blacklisted
[ INFO] [1553764392.222852698]: Plugin vision_pose_estimate loaded
[ INFO] [1553764392.229459403]: Plugin vision_pose_estimate initialized
[ INFO] [1553764392.229576252]: Plugin vision_speed_estimate loaded
[ INFO] [1553764392.233003872]: Plugin vision_speed_estimate initialized
[ INFO] [1553764392.233041079]: Plugin waypoint blacklisted
[ INFO] [1553764392.233058648]: Plugin wheel_odometry blacklisted
[ INFO] [1553764392.233070793]: Plugin wind_estimation blacklisted
[ INFO] [1553764392.233112250]: Autostarting mavlink via USB on PX4
[ INFO] [1553764392.233222385]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1553764392.233244599]: Built-in MAVLink package version: 2019.3.3
[ INFO] [1553764392.233270312]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad icarous matrixpilot paparazzi slugs standard uAvionix ualberta
[ INFO] [1553764392.233292901]: MAVROS started. MY ID 1.240, TARGET ID 1.240
[ INFO] [1553764393.176657797]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ WARN] [1553764395.180664299]: VER: broadcast request timeout, retries left 4
[ WARN] [1553764396.179255873]: VER: broadcast request timeout, retries left 3
[ WARN] [1553764402.179121079]: VER: unicast request timeout, retries left 2
[ INFO] [1553764403.177443891]: HP: requesting home position
[ WARN] [1553764407.181174134]: VER: unicast request timeout, retries left 1
[ WARN] [1553764407.181854282]: PR: request list timeout, retries left 2
[ WARN] [1553764408.183010643]: PR: request list timeout, retries left 1
[ WARN] [1553764409.183703879]: PR: request list timeout, retries left 0
[ WARN] [1553764412.186801537]: VER: unicast request timeout, retries left 0
[ INFO] [1553764413.176898788]: HP: requesting home position
[ WARN] [1553764417.189012767]: VER: your FCU don’t support AUTOPILOT_VERSION, switched to default capabilities
[ INFO] [1553764423.177623252]: HP: requesting home position
[ INFO] [1553764433.177757079]: HP: requesting home position
[ INFO] [1553764443.177226374]: HP: requesting home position
[ INFO] [1553764453.177163297]: HP: requesting home position
[ INFO] [1553764463.177830351]: HP: requesting home position
[ INFO] [1553764473.177638043]: HP: requesting home position
[ INFO] [1553764483.177478144]: HP: requesting home position
[ INFO] [1553764493.177867021]: HP: requesting home position

/diagnostics
/rosout
/rosout_agg
/tf
/tf_static
/uav/ground_pose
/uav1/mavlink/from
/uav1/mavlink/to
/uav1/mavros/actuator_control
/uav1/mavros/adsb/send
/uav1/mavros/adsb/vehicle
/uav1/mavros/altitude
/uav1/mavros/battery
/uav1/mavros/cam_imu_sync/cam_imu_stamp
/uav1/mavros/companion_process/status
/uav1/mavros/debug_value/debug
/uav1/mavros/debug_value/debug_vector
/uav1/mavros/debug_value/named_value_float
/uav1/mavros/debug_value/named_value_int
/uav1/mavros/debug_value/send
/uav1/mavros/extended_state
/uav1/mavros/fake_gps/vision
/uav1/mavros/global_position/compass_hdg
/uav1/mavros/global_position/global
/uav1/mavros/global_position/gp_lp_offset
/uav1/mavros/global_position/gp_origin
/uav1/mavros/global_position/home
/uav1/mavros/global_position/local
/uav1/mavros/global_position/raw/fix
/uav1/mavros/global_position/raw/gps_vel
/uav1/mavros/global_position/rel_alt
/uav1/mavros/global_position/set_gp_origin
/uav1/mavros/gps_rtk/send_rtcm
/uav1/mavros/home_position/home
/uav1/mavros/home_position/set
/uav1/mavros/imu/data
/uav1/mavros/imu/data_raw
/uav1/mavros/imu/diff_pressure
/uav1/mavros/imu/mag
/uav1/mavros/imu/static_pressure
/uav1/mavros/imu/temperature_baro
/uav1/mavros/imu/temperature_imu
/uav1/mavros/local_position/accel
/uav1/mavros/local_position/odom
/uav1/mavros/local_position/pose
/uav1/mavros/local_position/pose_cov
/uav1/mavros/local_position/velocity_body
/uav1/mavros/local_position/velocity_body_cov
/uav1/mavros/local_position/velocity_local
/uav1/mavros/log_transfer/raw/log_data
/uav1/mavros/log_transfer/raw/log_entry
/uav1/mavros/mocap/pose
/uav1/mavros/param/param_value
/uav1/mavros/setpoint_accel/accel
/uav1/mavros/setpoint_attitude/cmd_vel
/uav1/mavros/setpoint_attitude/thrust
/uav1/mavros/setpoint_position/global
/uav1/mavros/setpoint_position/local
/uav1/mavros/setpoint_velocity/cmd_vel
/uav1/mavros/setpoint_velocity/cmd_vel_unstamped
/uav1/mavros/state
/uav1/mavros/statustext/recv
/uav1/mavros/statustext/send
/uav1/mavros/target_actuator_control
/uav1/mavros/time_reference
/uav1/mavros/timesync_status
/uav1/mavros/trajectory/desired
/uav1/mavros/trajectory/generated
/uav1/mavros/trajectory/path
/uav1/mavros/vision_pose/pose
/uav1/mavros/vision_pose/pose_cov
/uav1/mavros/vision_speed/speed_twist_cov

rostopic echo -n1 /diagnostics
header:
seq: 481
stamp:
secs: 1553764708
nsecs: 689837892
frame_id: ‘’
status:

level: 0
name: "uav1/mavros: FCU connection"
message: "connected"
hardware_id: "/dev/ttyUSB0:115200"
values: 
  - 
    key: "Received packets:"
    value: "4051"
  - 
    key: "Dropped packets:"
    value: "0"
  - 
    key: "Buffer overruns:"
    value: "0"
  - 
    key: "Parse errors:"
    value: "0"
  - 
    key: "Rx sequence number:"
    value: "35"
  - 
    key: "Tx sequence number:"
    value: "199"
  - 
    key: "Rx total bytes:"
    value: "152697"
  - 
    key: "Tx total bytes:"
    value: "1629470"
  - 
    key: "Rx speed:"
    value: "694.000000"
  - 
    key: "Tx speed:"
    value: "7960.000000"
  • level: 2
    name: “uav1/mavros: GPS”
    message: “No satellites”
    hardware_id: “/dev/ttyUSB0:115200”
    values:

    key: "Satellites visible"
    value: "0"
    
    • key: “Fix type”
      value: “0”
    • key: “EPH (m)”
      value: “Unknown”
    • key: “EPV (m)”
      value: “Unknown”
  • level: 0
    name: “uav1/mavros: Heartbeat”
    message: “Normal”
    hardware_id: “/dev/ttyUSB0:115200”
    values:

    key: "Heartbeats since startup"
    value: "316"
    
    • key: “Frequency (Hz)”
      value: “1.000014”
    • key: “Vehicle type”
      value: “Quadrotor”
    • key: “Autopilot type”
      value: “PX4 Autopilot”
    • key: “Mode”
      value: “MANUAL”
    • key: “System status”
      value: “Standby”
  • level: 2
    name: “uav1/mavros: System”
    message: “Sensor helth”
    hardware_id: “/dev/ttyUSB0:115200”
    values:

    key: "Sensor present"
    value: "0x0006002F"
    
    • key: “Sensor enabled”
      value: “0x0021000B”
    • key: “Sensor helth”
      value: “0x0006002F”
    • key: “3D gyro”
      value: “Ok”
    • key: “3D accelerometer”
      value: “Ok”
    • key: “absolute pressure”
      value: “Ok”
    • key: “rc receiver”
      value: “Fail”
    • key: “AHRS subsystem health”
      value: “Fail”
    • key: “CPU Load (%)”
      value: “29.0”
    • key: “Drop rate (%)”
      value: “0.0”
    • key: “Errors comm”
      value: “0”
    • key: “Errors count #1
      value: “0”
    • key: “Errors count #2
      value: “0”
    • key: “Errors count #3
      value: “0”
    • key: “Errors count #4
      value: “0”
  • level: 0
    name: “uav1/mavros: Battery”
    message: “Normal”
    hardware_id: “/dev/ttyUSB0:115200”
    values:

    key: "Voltage"
    value: "15.34"
    
    • key: “Current”
      value: “0.2”
    • key: “Remaining”
      value: “67.0”

Another update:

I found in the parameters that “MAV_0_FORWARD” was disabled. I enabled this and now I can read messages off of “mavros/local_position/pose” and they match the messages I see from "mavros/vision_pose/pose". I noticed that with the Xbees at 115200 BAUD the MoCap streaming rate was crawling at ~2Hz. When I removed the Xbees and used and FTDI converted to wire my TELEM1 port to my base station this rate jumped to much much faster. So it seems now that the Xbees are not going to work, unless anyone else has and idea how to change that.

Unfortunately, I still cannot activate "OFFBOARD" mode. I have some more complicated collision avoidance code I would like to run, but for now I can’t even get the basic "offb_node.cpp" example to arm correctly. Right now I am testing with the companion computer linked to my base station via an FTDI cable at 921600 BAUD. I have good data on "mavros/local_position/pose" but still no arming.

Again, any input is welcome. Thanks!

Some success:

Using the FTDI connection to my base station computer at 921600 BAUD I was able to get "OFFBOARD" mode to run. When I run "roslaunch mavros px4.launch" there is a portion of the connection banner that states MAVROS started. "MY ID 1.240, TARGET ID 1.1". This was misleading to me, and I thought I should make my "px4.launch" file "tgt_system" and "tgt_component" match these values. This was a mistake, don’t change these values in the "px4.launch" file! When I changed the "tgt_system" and "tgt_component" values both back to 1 I was able to get "OFFBOARD" to activate.

Since I was doing this over FTDI connection to my base station computer I still need to get this to run wirelessly. As I stated earlier, the Xbee modules at 115200 seem to lack the necessary bandwidth to pass MoCap data. I am now working with my Pi Zero and a Maverick Lite image to see if I can set up an onboard connection at 921600 BAUD running a ROS master node onboard and sending the information offboard wirelessly. So far I am a bit skeptical about this approach, because with roscore running on my Pi Zero I’m already at 40% CPU.

If anyone has any ideas on how I can communicate MoCap data to my quad with a small piece of electronics (preferably the Pi Zero, as I already have a bunch of these), I am open to ideas.

Thanks!

Another issue:

I was able to connect to my base station computer via FTDI no problem. However, when I connect my Pi Zero to my Pixhawk by running "roslaunch mavros px4.launch" I get a whole bunch of "[ WARN] [1553858263.330065973]: PR: request param #2 timeout, retries left 0, and 530 params still missing" which I think is hogging all of my bandwidth and causing Heartbeat timeouts. Currently I’m running at 921600 BAUD. Does anyone know how to disable to parameter download, or resolve this issue?

I faced almost all the issues you had. Let me try the MAV_0_FORWARD = 1 now

And, no luck :frowning: Did you make any progress?