Open leocencetti opened 3 years ago
Hi @leocencetti If you don't get /mavros/state msgs is because you are not connected to the FMU or there's a further problem with your connection.
The setup you describe with the Jetson Nano and Pixhawk is compatible and works, so it has to be a configuration problem.
I would try a few things, first make sure that you're connecting the telemetry cables to the correct pins on the Jetson (https://www.jetsonhacks.com/nvidia-jetson-nano-j41-header-pinout/) board TX is pin 8 and board RX is pin 10. You also need to connect the GND to one of the GND pins of the Jetson.
By default the Nano is publishing console data on ttyTHS1, which will interfere with what you want to do. Make sure you disable the running service with:
systemctl stop nvgetty
systemctl disable nvgetty
udevadm trigger
Then validate that ttyTHS1 is working well, you can follow this tutorial (https://www.jetsonhacks.com/2019/10/10/jetson-nano-uart/)
Then I would try to launch MAVROS with the roscore running on the Jetson without the gcs_url and check if you have a valid connection. (ex: rostopic echo /mavros/state and check that you receive connected: True)
You don't describe how you're using the roscore, but I think that in order to connect the Jetson with the other computer you are going to have to configure the ROS_MASTER_URI and ROS_IP. I'm not sure if that can be part of the problem.
Hi @antonio-sc66, thank you for the reply.
As you suggested, I have verified the telemetry connection between the Jetson and the TELEM2
port of the PixHawk, which does indeed work (tested successfully with the tutorial you linked).
Then I would try to launch MAVROS with the roscore running on the Jetson without the gcs_url and check if you have a valid connection. (ex: rostopic echo /mavros/state and check that you receive connected: True)
The nvgetty
service was enabled, thus I have disabled it.
Nevertheless, launching MAVROS with roscore
running on the Jetson and without the gcs_url
option (as I had already done previously) still gives me the same outputas before: /diagnostics
says FCU is disconnected, and /mavros/state
is silent.
The same goes with the gcs_url
option.
I am still able to read data from other telemetry topics (e.g. /drone_1/mavros/imu/data
), thus I would rule out hardware connection problems...
I have also tried to connect the Jetson to both TELEM1
and TELEM2
ports, with the same results. As a reference, here is my configuration of the MavLink parameters (from QGC):
You don't describe how you're using the roscore, but I think that in order to connect the Jetson with the other computer you are going to have to configure the ROS_MASTER_URI and ROS_IP. I'm not sure if that can be part of the problem.
Yes, I have the following ENV configuration:
ROS_MASTER_URI=http://192.168.0.105:11311
ROS_IP=192.168.0.223
ROS_MASTER_URI=http://localhost:11311
ROS_IP=192.168.0.105
where 192.168.0.105
is the IP of the ground station and 192.168.0.223
the IP of the Jetson.
@leocencetti You have a really low MAV_1_RATE try a higher value like 921600. The parameters described here (https://docs.px4.io/v1.9.0/en/peripherals/mavlink_peripherals.html#example) work for me.
I've seen that you use a custom MAV_SYS_ID, MAVROS has parameters for the sys_id and comp_id in the launch file, they're tgt_system and tgt_component. Make sure you have the same values in MAVROS and PX4.
@antonio-sc66 sorry for the delay...
You have a really low MAV_1_RATE try a higher value like 921600. The parameters described here (https://docs.px4.io/v1.9.0/en/peripherals/mavlink_peripherals.html#example) work for me.
changed them to 57600
and 921600
respectively, as said in the guide
I've seen that you use a custom MAV_SYS_ID, MAVROS has parameters for the sys_id and comp_id in the launch file, they're tgt_system and tgt_component. Make sure you have the same values in MAVROS and PX4. Yes, we have the defaults of the launch file matching the "custom" ID
<launch> <!-- vim: set ft=xml noet : --> <!-- example launch script for PX4 based FCU's -->
<arg name="fcu_url" default="/dev/ttyACM0:57600" />
<arg name="gcs_url" default="" />
<arg name="tgt_system" default="9" />
<arg name="tgt_component" default="9" />
<arg name="log_output" default="screen" />
<arg name="fcu_protocol" default="v2.0" />
<arg name="respawn_mavros" default="false" />
<include file="$(find mavros)/launch/node.launch">
<arg name="pluginlists_yaml" value="$(find mavros)/launch/px4_pluginlists.yaml" />
<arg name="config_yaml" value="$(find mavros)/launch/px4_config.yaml" />
<arg name="fcu_url" value="$(arg fcu_url)" />
<arg name="gcs_url" value="$(arg gcs_url)" />
<arg name="tgt_system" value="$(arg tgt_system)" />
<arg name="tgt_component" value="$(arg tgt_component)" />
<arg name="log_output" value="$(arg log_output)" />
<arg name="fcu_protocol" value="$(arg fcu_protocol)" />
<arg name="respawn_mavros" default="$(arg respawn_mavros)" />
</include>
Unfortunately, still the same results,` /diagnostics` says FCU is disconnected, and `/mavros/state` is silent.
@leocencetti. Well, that seems strange, I'm not sure what else you can try
@leocencetti May be a little late for you but: In the launch file you've got tgt_component
set to 9, but your param screenshot shows MAV_COMP_ID
set to 1. That might be the problem.
Issue details
Hi, I am trying to put a multi-copter in
OFFBOARD
mode, without success. My setup is the following:px4.launch
as follows:where
/dev/ttyTHS1
is the PixHawk interface and192.168.0.105
is the ground station computer (ROS master).POSITION
control mode works fine).roscore
.I have tried:
/drone_1/setpoint_position/local
topic and then switching toOFFBOARD
mode via mapped RC switch. The mode is rejected and the following message is printed:offb_node
example from here (changing the topics accordingly, of course). The node gets stuck in the following while loop, sincecurrent_state.connected
never evaluates totrue
:The example works fine in SITL.
From further inspection, the problem seems to be with the
/drone_1/mavros/state
topic being silent:If echoed, the topic returns a single (I guess default) message:
I do receive the
HEARTBEAT
(from MAVLink Inspector in QGroundControl) as well as all other MAVROS topics (IMU, Position, Attitude, etc...).MAVROS version and platform
Mavros: 1.5.2 ROS: melodic Ubuntu: 16.04 and 18.04
Autopilot type and version
[ ] ArduPilot [X] PX4
Version: 1.11.2
Node logs
[click to expand]
``` started roslaunch server http://192.168.0.223:36127/ SUMMARY ======== CLEAR PARAMETERS * /drone_1/mavros/ PARAMETERS * /drone_1/mavros/cmd/use_comp_id_system_control: False * /drone_1/mavros/conn/heartbeat_rate: 1.0 * /drone_1/mavros/conn/system_time_rate: 1.0 * /drone_1/mavros/conn/timeout: 10.0 * /drone_1/mavros/conn/timesync_rate: 10.0 * /drone_1/mavros/distance_sensor/hrlv_ez4_pub/field_of_view: 0.0 * /drone_1/mavros/distance_sensor/hrlv_ez4_pub/frame_id: hrlv_ez4_sonar * /drone_1/mavros/distance_sensor/hrlv_ez4_pub/id: 0 * /drone_1/mavros/distance_sensor/hrlv_ez4_pub/orientation: PITCH_270 * /drone_1/mavros/distance_sensor/hrlv_ez4_pub/send_tf: True * /drone_1/mavros/distance_sensor/hrlv_ez4_pub/sensor_position/x: 0.0 * /drone_1/mavros/distance_sensor/hrlv_ez4_pub/sensor_position/y: 0.0 * /drone_1/mavros/distance_sensor/hrlv_ez4_pub/sensor_position/z: -0.1 * /drone_1/mavros/distance_sensor/laser_1_sub/id: 3 * /drone_1/mavros/distance_sensor/laser_1_sub/orientation: PITCH_270 * /drone_1/mavros/distance_sensor/laser_1_sub/subscriber: True * /drone_1/mavros/distance_sensor/lidarlite_pub/field_of_view: 0.0 * /drone_1/mavros/distance_sensor/lidarlite_pub/frame_id: lidarlite_laser * /drone_1/mavros/distance_sensor/lidarlite_pub/id: 1 * /drone_1/mavros/distance_sensor/lidarlite_pub/orientation: PITCH_270 * /drone_1/mavros/distance_sensor/lidarlite_pub/send_tf: True * /drone_1/mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0 * /drone_1/mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0 * /drone_1/mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1 * /drone_1/mavros/distance_sensor/sonar_1_sub/id: 2 * /drone_1/mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270 * /drone_1/mavros/distance_sensor/sonar_1_sub/subscriber: True * /drone_1/mavros/fake_gps/eph: 2.0 * /drone_1/mavros/fake_gps/epv: 2.0 * /drone_1/mavros/fake_gps/fix_type: 3 * /drone_1/mavros/fake_gps/geo_origin/alt: 408.0 * /drone_1/mavros/fake_gps/geo_origin/lat: 47.3667 * /drone_1/mavros/fake_gps/geo_origin/lon: 8.55 * /drone_1/mavros/fake_gps/gps_rate: 5.0 * /drone_1/mavros/fake_gps/mocap_transform: True * /drone_1/mavros/fake_gps/satellites_visible: 5 * /drone_1/mavros/fake_gps/tf/child_frame_id: fix * /drone_1/mavros/fake_gps/tf/frame_id: map * /drone_1/mavros/fake_gps/tf/listen: False * /drone_1/mavros/fake_gps/tf/rate_limit: 10.0 * /drone_1/mavros/fake_gps/tf/send: False * /drone_1/mavros/fake_gps/use_mocap: True * /drone_1/mavros/fake_gps/use_vision: False * /drone_1/mavros/fcu_protocol: v2.0 * /drone_1/mavros/fcu_url: /dev/ttyTHS1:921600 * /drone_1/mavros/gcs_url: udp://:14555@192.... * /drone_1/mavros/global_position/child_frame_id: base_link * /drone_1/mavros/global_position/frame_id: map * /drone_1/mavros/global_position/gps_uere: 1.0 * /drone_1/mavros/global_position/rot_covariance: 99999.0 * /drone_1/mavros/global_position/tf/child_frame_id: base_link * /drone_1/mavros/global_position/tf/frame_id: map * /drone_1/mavros/global_position/tf/global_frame_id: earth * /drone_1/mavros/global_position/tf/send: False * /drone_1/mavros/global_position/use_relative_alt: True * /drone_1/mavros/image/frame_id: px4flow * /drone_1/mavros/imu/angular_velocity_stdev: 0.0003490659 // 0... * /drone_1/mavros/imu/frame_id: base_link * /drone_1/mavros/imu/linear_acceleration_stdev: 0.0003 * /drone_1/mavros/imu/magnetic_stdev: 0.0 * /drone_1/mavros/imu/orientation_stdev: 1.0 * /drone_1/mavros/landing_target/camera/fov_x: 2.0071286398 * /drone_1/mavros/landing_target/camera/fov_y: 2.0071286398 * /drone_1/mavros/landing_target/image/height: 480 * /drone_1/mavros/landing_target/image/width: 640 * /drone_1/mavros/landing_target/land_target_type: VISION_FIDUCIAL * /drone_1/mavros/landing_target/listen_lt: False * /drone_1/mavros/landing_target/mav_frame: LOCAL_NED * /drone_1/mavros/landing_target/target_size/x: 0.3 * /drone_1/mavros/landing_target/target_size/y: 0.3 * /drone_1/mavros/landing_target/tf/child_frame_id: camera_center * /drone_1/mavros/landing_target/tf/frame_id: landing_target * /drone_1/mavros/landing_target/tf/listen: False * /drone_1/mavros/landing_target/tf/rate_limit: 10.0 * /drone_1/mavros/landing_target/tf/send: True * /drone_1/mavros/local_position/frame_id: map * /drone_1/mavros/local_position/tf/child_frame_id: base_link * /drone_1/mavros/local_position/tf/frame_id: map * /drone_1/mavros/local_position/tf/send: False * /drone_1/mavros/local_position/tf/send_fcu: False * /drone_1/mavros/mission/pull_after_gcs: True * /drone_1/mavros/mission/use_mission_item_int: True * /drone_1/mavros/mocap/use_pose: True * /drone_1/mavros/mocap/use_tf: False * /drone_1/mavros/odometry/fcu/odom_child_id_des: base_link * /drone_1/mavros/odometry/fcu/odom_parent_id_des: map * /drone_1/mavros/plugin_blacklist: ['safety_area', '... * /drone_1/mavros/plugin_whitelist: [] * /drone_1/mavros/px4flow/frame_id: px4flow * /drone_1/mavros/px4flow/ranger_fov: 0.118682 * /drone_1/mavros/px4flow/ranger_max_range: 5.0 * /drone_1/mavros/px4flow/ranger_min_range: 0.3 * /drone_1/mavros/safety_area/p1/x: 1.0 * /drone_1/mavros/safety_area/p1/y: 1.0 * /drone_1/mavros/safety_area/p1/z: 1.0 * /drone_1/mavros/safety_area/p2/x: -1.0 * /drone_1/mavros/safety_area/p2/y: -1.0 * /drone_1/mavros/safety_area/p2/z: -1.0 * /drone_1/mavros/setpoint_accel/send_force: False * /drone_1/mavros/setpoint_attitude/reverse_thrust: False * /drone_1/mavros/setpoint_attitude/tf/child_frame_id: target_attitude * /drone_1/mavros/setpoint_attitude/tf/frame_id: map * /drone_1/mavros/setpoint_attitude/tf/listen: False * /drone_1/mavros/setpoint_attitude/tf/rate_limit: 50.0 * /drone_1/mavros/setpoint_attitude/use_quaternion: False * /drone_1/mavros/setpoint_position/mav_frame: LOCAL_NED * /drone_1/mavros/setpoint_position/tf/child_frame_id: target_position * /drone_1/mavros/setpoint_position/tf/frame_id: map * /drone_1/mavros/setpoint_position/tf/listen: False * /drone_1/mavros/setpoint_position/tf/rate_limit: 50.0 * /drone_1/mavros/setpoint_raw/thrust_scaling: 1.0 * /drone_1/mavros/setpoint_velocity/mav_frame: LOCAL_NED * /drone_1/mavros/startup_px4_usb_quirk: True * /drone_1/mavros/sys/disable_diag: False * /drone_1/mavros/sys/min_voltage: 10.0 * /drone_1/mavros/target_component_id: 1 * /drone_1/mavros/target_system_id: 1 * /drone_1/mavros/tdr_radio/low_rssi: 40 * /drone_1/mavros/time/time_ref_source: fcu * /drone_1/mavros/time/timesync_avg_alpha: 0.6 * /drone_1/mavros/time/timesync_mode: MAVLINK * /drone_1/mavros/vibration/frame_id: base_link * /drone_1/mavros/vision_pose/tf/child_frame_id: vision_estimate * /drone_1/mavros/vision_pose/tf/frame_id: odom * /drone_1/mavros/vision_pose/tf/listen: False * /drone_1/mavros/vision_pose/tf/rate_limit: 10.0 * /drone_1/mavros/vision_speed/listen_twist: True * /drone_1/mavros/vision_speed/twist_cov: True * /drone_1/mavros/wheel_odometry/child_frame_id: base_link * /drone_1/mavros/wheel_odometry/count: 2 * /drone_1/mavros/wheel_odometry/frame_id: odom * /drone_1/mavros/wheel_odometry/send_raw: True * /drone_1/mavros/wheel_odometry/send_twist: False * /drone_1/mavros/wheel_odometry/tf/child_frame_id: base_link * /drone_1/mavros/wheel_odometry/tf/frame_id: odom * /drone_1/mavros/wheel_odometry/tf/send: False * /drone_1/mavros/wheel_odometry/use_rpm: False * /drone_1/mavros/wheel_odometry/vel_error: 0.1 * /drone_1/mavros/wheel_odometry/wheel0/radius: 0.05 * /drone_1/mavros/wheel_odometry/wheel0/x: 0.0 * /drone_1/mavros/wheel_odometry/wheel0/y: -0.15 * /drone_1/mavros/wheel_odometry/wheel1/radius: 0.05 * /drone_1/mavros/wheel_odometry/wheel1/x: 0.0 * /drone_1/mavros/wheel_odometry/wheel1/y: 0.15 * /rosdistro: melodic * /rosversion: 1.14.10 NODES /drone_1/ mavros (mavros/mavros_node) ROS_MASTER_URI=http://192.168.0.105:11311 process[drone_1/mavros-1]: started with pid [7557] [ INFO] [1612973454.136470861]: FCU URL: /dev/ttyTHS1:921600 [ INFO] [1612973454.145396842]: serial0: device: /dev/ttyTHS1 @ 921600 bps [ INFO] [1612973454.146225747]: GCS URL: udp://:14555@192.168.0.105:14550 [ INFO] [1612973454.146573299]: udp1: Bind address: 0.0.0.0:14555 [ INFO] [1612973454.146731476]: udp1: Remote address: 192.168.0.105:14550 [ INFO] [1612973454.185702113]: udp1: Remote address: 192.168.0.105:14550 [ INFO] [1612973454.186093363]: Plugin 3dr_radio loaded [ INFO] [1612973454.194870021]: Plugin 3dr_radio initialized [ INFO] [1612973454.195038979]: Plugin actuator_control loaded [ INFO] [1612973454.216444530]: Plugin actuator_control initialized [ INFO] [1612973454.226957801]: Plugin adsb loaded [ INFO] [1612973454.246000438]: Plugin adsb initialized [ INFO] [1612973454.246346479]: Plugin altitude loaded [ INFO] [1612973454.252137046]: Plugin altitude initialized [ INFO] [1612973454.252316369]: Plugin cam_imu_sync loaded [ INFO] [1612973454.256030271]: Plugin cam_imu_sync initialized [ INFO] [1612973454.256219386]: Plugin command loaded [ INFO] [1612973454.289286123]: Plugin command initialized [ INFO] [1612973454.289478727]: Plugin companion_process_status loaded [ INFO] [1612973454.306126366]: Plugin companion_process_status initialized [ INFO] [1612973454.306294752]: Plugin debug_value loaded [ INFO] [1612973454.335970503]: Plugin debug_value initialized [ INFO] [1612973454.336036440]: Plugin distance_sensor blacklisted [ INFO] [1612973454.336239044]: Plugin esc_status loaded [ INFO] [1612973454.346294919]: Plugin esc_status initialized [ INFO] [1612973454.346555232]: Plugin fake_gps loaded [ INFO] [1612973454.455827360]: Plugin fake_gps initialized [ INFO] [1612973454.456065693]: Plugin ftp loaded [ INFO] [1612973454.493091489]: Plugin ftp initialized [ INFO] [1612973454.493363468]: Plugin global_position loaded [ INFO] [1612973454.596412270]: Plugin global_position initialized [ INFO] [1612973454.596667009]: Plugin gps_rtk loaded [ INFO] [1612973454.614447825]: Plugin gps_rtk initialized [ INFO] [1612973454.614681262]: Plugin gps_status loaded [ INFO] [1612973454.629371403]: Plugin gps_status initialized [ INFO] [1612973454.629625049]: Plugin hil loaded [ INFO] [1612973454.714480275]: Plugin hil initialized [ INFO] [1612973454.714760796]: Plugin home_position loaded [ INFO] [1612973454.735791243]: Plugin home_position initialized [ INFO] [1612973454.736100045]: Plugin imu loaded [ INFO] [1612973454.781034062]: Plugin imu initialized [ INFO] [1612973454.781295208]: Plugin landing_target loaded [ INFO] [1612973454.881687189]: Plugin landing_target initialized [ INFO] [1612973454.881978543]: Plugin local_position loaded [ INFO] [1612973454.921599128]: Plugin local_position initialized [ INFO] [1612973454.921846263]: Plugin log_transfer loaded [ INFO] [1612973454.938543590]: Plugin log_transfer initialized [ INFO] [1612973454.938824267]: Plugin manual_control loaded [ INFO] [1612973454.958653153]: Plugin manual_control initialized [ INFO] [1612973454.958911903]: Plugin mocap_pose_estimate loaded [ INFO] [1612973454.985592188]: Plugin mocap_pose_estimate initialized [ INFO] [1612973454.985790261]: Plugin mount_control loaded [ INFO] [1612973455.008717894]: Plugin mount_control initialized [ INFO] [1612973455.008921071]: Plugin obstacle_distance loaded [ INFO] [1612973455.028616155]: Plugin obstacle_distance initialized [ INFO] [1612973455.028801519]: Plugin odom loaded [ INFO] [1612973455.060391748]: Plugin odom initialized [ INFO] [1612973455.060648674]: Plugin onboard_computer_status loaded [ INFO] [1612973455.079800530]: Plugin onboard_computer_status initialized [ INFO] [1612973455.080053707]: Plugin param loaded [ INFO] [1612973455.095166764]: Plugin param initialized [ INFO] [1612973455.095359941]: Plugin play_tune loaded [ INFO] [1612973455.110932113]: Plugin play_tune initialized [ INFO] [1612973455.111117425]: Plugin px4flow loaded [ INFO] [1612973455.155985453]: Plugin px4flow initialized [ INFO] [1612973455.156069046]: Plugin rangefinder blacklisted [ INFO] [1612973455.156363682]: Plugin rc_io loaded [ INFO] [1612973455.179142669]: Plugin rc_io initialized [ INFO] [1612973455.179300533]: Plugin safety_area blacklisted [ INFO] [1612973455.179601783]: Plugin setpoint_accel loaded [ INFO] [1612973455.210466335]: Plugin setpoint_accel initialized [ INFO] [1612973455.210812845]: Plugin setpoint_attitude loaded [ INFO] [1612973455.270193983]: Plugin setpoint_attitude initialized [ INFO] [1612973455.270565962]: Plugin setpoint_position loaded [ INFO] [1612973455.385554074]: Plugin setpoint_position initialized [ INFO] [1612973455.385886938]: Plugin setpoint_raw loaded [ INFO] [1612973455.456585669]: Plugin setpoint_raw initialized [ INFO] [1612973455.456870929]: Plugin setpoint_trajectory loaded [ INFO] [1612973455.495712921]: Plugin setpoint_trajectory initialized [ INFO] [1612973455.495982973]: Plugin setpoint_velocity loaded [ INFO] [1612973455.546426359]: Plugin setpoint_velocity initialized [ INFO] [1612973455.546734744]: Plugin sys_status loaded [ INFO] [1612973455.633186271]: Plugin sys_status initialized [ INFO] [1612973455.633590646]: Plugin sys_time loaded [ INFO] [1612973455.688743298]: TM: Timesync mode: MAVLINK [ INFO] [1612973455.697533914]: Plugin sys_time initialized [ INFO] [1612973455.697788237]: Plugin trajectory loaded [ INFO] [1612973455.742813347]: Plugin trajectory initialized [ INFO] [1612973455.743127931]: Plugin vfr_hud loaded [ INFO] [1612973455.747268916]: Plugin vfr_hud initialized [ INFO] [1612973455.747342874]: Plugin vibration blacklisted [ INFO] [1612973455.747604332]: Plugin vision_pose_estimate loaded [ INFO] [1612973455.817745147]: Plugin vision_pose_estimate initialized [ INFO] [1612973455.818049209]: Plugin vision_speed_estimate loaded [ INFO] [1612973455.852791309]: Plugin vision_speed_estimate initialized [ INFO] [1612973455.853246621]: Plugin waypoint loaded [ INFO] [1612973455.894186944]: Plugin waypoint initialized [ INFO] [1612973455.894358194]: Plugin wheel_odometry blacklisted [ INFO] [1612973455.894832933]: Plugin wind_estimation loaded [ INFO] [1612973455.901625999]: Plugin wind_estimation initialized [ INFO] [1612973455.901722041]: Autostarting mavlink via USB on PX4 [ INFO] [1612973455.901821207]: Built-in SIMD instructions: ARM NEON [ INFO] [1612973455.901973967]: Built-in MAVLink package version: 2021.1.4 [ INFO] [1612973455.902233446]: Known MAVLink dialects: common ardupilotmega ASLUAV all autoquad icarous matrixpilot paparazzi standard uAvionix ualberta [ INFO] [1612973455.902326155]: MAVROS started. MY ID 1.240, TARGET ID 1.1 [ WARN] [1612973455.920141709]: CMD: Unexpected command 519, result 0 [ WARN] [1612973455.980778940]: GP: No GPS fix [ INFO] [1612973456.000759284]: IMU: Attitude quaternion IMU detected! [ERROR] [1612973456.192216746]: FCU: Connection to ground station lost [ INFO] [1612973456.262523394]: IMU: High resolution IMU detected! [ INFO] [1612973456.402931324]: RC_CHANNELS message detected! [ INFO] [1612973457.199246975]: FCU: Data link regained [ INFO] [1612973462.802783483]: FCU: [logger] /fs/microsd/log/2021-02-09/16_40_43.ulg [ INFO] [1612973468.829121697]: FCU: Takeoff detected [ WARN] [1612973486.079936815]: GP: No GPS fix [ WARN] [1612973516.080519894]: GP: No GPS fix ```Diagnostics
Result of:
[click to expand]
``` header: seq: 6862 stamp: secs: 1612969225 nsecs: 213224776 frame_id: '' status: - level: 0 name: "drone_1/mavros: GCS bridge" message: "connected" hardware_id: "udp://:14555@192.168.0.105:14550" values: - key: "Received packets:" value: "10399" - key: "Dropped packets:" value: "0" - key: "Buffer overruns:" value: "0" - key: "Parse errors:" value: "0" - key: "Rx sequence number:" value: "120" - key: "Tx sequence number:" value: "0" - key: "Rx total bytes:" value: "205926" - key: "Tx total bytes:" value: "79752205" - key: "Rx speed:" value: "78.000000" - key: "Tx speed:" value: "21830.000000" ```Result of:
[click to expand]
``` header: seq: 208 stamp: secs: 1612973383 nsecs: 878466767 frame_id: '' status: - level: 1 name: "mavros: FCU connection" message: "not connected" hardware_id: "/dev/ttyTHS1:921600" values: - key: "Received packets:" value: "11181" - key: "Dropped packets:" value: "0" - key: "Buffer overruns:" value: "0" - key: "Parse errors:" value: "0" - key: "Rx sequence number:" value: "76" - key: "Tx sequence number:" value: "0" - key: "Rx total bytes:" value: "385116" - key: "Tx total bytes:" value: "92283" - key: "Rx speed:" value: "2171.000000" - key: "Tx speed:" value: "526.000000" - level: 2 name: "mavros: GPS" message: "No satellites" hardware_id: "/dev/ttyTHS1:921600" values: - key: "Satellites visible" value: "0" - key: "Fix type" value: "0" - key: "EPH (m)" value: "99.99" - key: "EPV (m)" value: "99.99" - level: 2 name: "mavros: Heartbeat" message: "No events recorded." hardware_id: "/dev/ttyTHS1:921600" 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: 2 name: "mavros: System" message: "Sensor health" hardware_id: "/dev/ttyTHS1:921600" values: - key: "Sensor present" value: "0x1227002F" - key: "Sensor enabled" value: "0x1221002F" - key: "Sensor health" value: "0x1227000F" - key: "3D gyro" value: "Ok" - key: "3D accelerometer" value: "Ok" - key: "3D magnetometer" value: "Ok" - key: "absolute pressure" value: "Ok" - key: "GPS" value: "Fail" - key: "rc receiver" value: "Ok" - key: "AHRS subsystem health" value: "Ok" - key: "Battery" value: "Ok" - key: "CPU Load (%)" value: "53.6" - 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/ttyTHS1:921600" values: - key: "Voltage" value: "11.18" - key: "Current" value: "0.8" - key: "Remaining" value: "42.0" - level: 0 name: "mavros: Time Sync" message: "Normal" hardware_id: "/dev/ttyTHS1:921600" values: - key: "Timesyncs since startup" value: "2770" - key: "Frequency (Hz)" value: "9.999952" - key: "Last RTT (ms)" value: "2.145779" - key: "Mean RTT (ms)" value: "1.584656" - key: "Last remote time (s)" value: "3397.344842000" - key: "Estimated time offset (s)" value: "1612969986.486017704" - level: 1 name: "mavros: 3DR Radio" message: "Low remote RSSI" hardware_id: "/dev/ttyTHS1:921600" values: - key: "RSSI" value: "67" - key: "RSSI (dBm)" value: "-91.7" - key: "Remote RSSI" value: "0" - key: "Remote RSSI (dBm)" value: "-127.0" - key: "Tx buffer (%)" value: "100" - key: "Noice level" value: "69" - key: "Remote noice level" value: "0" - key: "Rx errors" value: "0" - key: "Fixed" value: "0" ```