PX4 / PX4-Autopilot

PX4 Autopilot Software
https://px4.io
BSD 3-Clause "New" or "Revised" License
8.32k stars 13.43k forks source link

Issues with Mavlink and GPS on Kakute f7 #13728

Open felix-west opened 4 years ago

felix-west commented 4 years ago

I'm currently trying to integrate a GPS module controlled by an stm32 onto my drone and make it communicate with the flight controller (holybro kakute f7) via Mavlink. To do this the stm32 will read and process all GPS data and send a Mavlink message, currently a GPS_RAW_INT message with message ID 24. (see discussion https://discuss.px4.io/t/what-mavlink-messages-are-used-for-the-gps-toolbar-indicator/7548)

The code to create and send a test message with baud rate 57600, 8bit message and 1 bit stop bit on the stm32 is the following:

uint8_t buf[160];
volatile uint16_t n;
mavlink_message_t msg;
while (1){
        for(int i=0; i<160; i++){
                buf[i]=0;
            }
                 n= mavlink_msg_gps_raw_int_pack(1,220,&msg, HAL_GetTick()*1000.0, 3, 100, 100, -20, 1, 2, 3,4, 10, 0, 00,00,00,1*00000.0);
                 n = mavlink_msg_to_send_buffer(buf, &msg);
            volatile int xx=0;
            while(xx<n){
                sendserial( (uint8_t*) &buf[xx], (n-xx>10) ? 10 : n-xx);
                xx=xx+10;
            }
}

When sniffing the serial output of the stm device baud rate 57600 I get something along the lines of the following hex output: fd 1e 00 00 64 01 dc 18 00 00 60 c3 3f 01 00 00 00 00 64 00 00 00 64 00 00 00 ec ff ff ff 01 00 02 00 03 00 04 00 03 0a 52 fe

Decoding it shows me that it is the correct message, the serial port is also configured correctly, with the start being fd, sysid set as 1, compid at 220, and so forth. However, when attaching QGroundControl to my flight controller with the stm32 attached and sending shows no messages with ID 24 as incoming. The GPS indicator also shows no change.

The next step I took was analyzing the traffic between the flight controller and QGC. To do this I sniffed my serial in/outputs on the corresponding ports. The incoming packets (on my PC) looked like they corresponded to the Mavlink messages being sent by the flight controller to QGC, which were also the packets being shown in the Mavlink inspector widget. Analyzing the outgoing traffic showed me the following:

fd 09 00 00 99 ff 00 00 00 00 00 00 00 00 06 08 c0 04 03 15 3c
fd 0e 00 00 9a ff 00 04 00 00 89 28 cb 07 00 00 00 00 0c 00 00 00 01 01 a8 0a
fd 09 00 00 9b ff 00 00 00 00 00 00 00 00 06 08 c0 04 03 24 28

I haven't gotten around to deciphering that, but it only looks like a hearbeat message from the QGC to me, something which a flight controller would not NEED to operate by itself. Furthermore, when I try to manually arm the drone using QGC the command constantly gets rejected. There is no clear reason for this. The setting for disabling the requirement for GPS lock is set and I'm using a fresh battery. I will have to check each of the onboard sensors tomorrow to check if one of them is causing the issue, however to me it seems right now that the flight controller is not accepting Mavlink messages correctly right now.

Essentially I have two questions right now: Are Mavlink messages being randomly rejected by the flight controller, including command messages as well as GPS messages, and if that is not the case why does the flight controller not react to the incoming message from the stm32, giving it all the GPS information it needs. In that case, does the flight controller not listen to Mavlink messages but instead only to the NMEA protocol?

bkueng commented 4 years ago

Hi A few things:

felix-west commented 4 years ago

Hi A few things:

  • GPS_RAW_INT is not handled as incoming message, it is only sent as outgoing message. It is proably best to add a separate message if you want to use it as incoming message (to avoid confusion).

I'm guessing this is the problem. But how do I find out what the valid incoming and outgoing messages are? There is no hint to this on the messages page (https://mavlink.io/en/messages/common.html) or on the page for the kakute f7 (https://docs.px4.io/master/en/flight_controller/kakutef7.html). Are these messages then the same for all boards, or are some messages process on some FC and not on others? By adding a separate message you probably mean adding my own custom message in the Mavlink library?

  • you need to make sure to run MAVLink on the port you send mavlink messages to the FC (check the MAV_x_CONFIG params and the ports of the Kakute F7. On the shell you can check with mavlink status.

Doing this returns with my current settings, with the Radio module on Telem1, the GPS module's output on Rx of Telem2 and my RC controller on pin R6:

nsh> mavlink status
instance #0:
        GCS heartbeat:  218642 us ago
        mavlink chan: #0
        type:           GENERIC LINK OR RADIO
        flow control: ON
        rates:
          tx: 0.980 kB/s
          txerr: 0.000 kB/s
          tx rate mult: 0.777
          tx rate max: 1200 B/s
          rx: 0.020 kB/s
        FTP enabled: YES, TX enabled: YES
        mode: Normal
        MAVLink version: 2
        transport protocol: serial (/dev/ttyS0 @57600)
        ping statistics:
          last: 265.96 ms
          mean: 205.52 ms
          max: 504.86 ms
          min: 112.74 ms
          dropped packets: 40

instance #1:
        mavlink chan: #1
        type:           GENERIC LINK OR RADIO
        flow control: ON
        rates:
          tx: 0.557 kB/s
          txerr: 0.000 kB/s
          tx rate mult: 0.424
          tx rate max: 1200 B/s
          rx: 0.210 kB/s
        FTP enabled: YES, TX enabled: YES
        mode: Normal
        MAVLink version: 2
        transport protocol: serial (/dev/ttyS1 @57600)

It essentially tells me that the settings I entered were accepted. Also, the GCS is in fact able to communicate with the FC and heartbeat packets are not dropped all the time. As far as I know the connection between the two is good enough for now. This is also the confirmation that the data from the GPS module arrives on the FC and is at least readable for it. So unfortunately, I did not gain much new usable information from this.

I also have a question to the Mavlink mode though. To me the description sounds like which messages are accepted and processed by the corresponding input. However, I found no documentation as to what these are exactly. How are mode "Normal" and "Onboard" different for example? Also, there is the option in QGC to assing GPS_x_CONFIG to the same pin pair as Mavlink messages. If both are applied to the same pair, what does that mean? Does GPS_x_CONFIG allow GPS related Mavlink messages to be accepted, or does it listen to NMEA protocols? Is there any documentation on this?

bkueng commented 4 years ago

The messages are independent from the board.

By adding a separate message you probably mean adding my own custom message in the Mavlink library?

Yes.

So unfortunately, I did not gain much new usable information from this.

You use it to test the connection between the stm32 and the FC.

To me the description sounds like which messages are accepted and processed by the corresponding input. However, I found no documentation as to what these are exactly. How are mode "Normal" and "Onboard" different for example?

It defines the set of outgoing messages, that are continuously streamed.

Does GPS_x_CONFIG allow GPS related Mavlink messages to be accepted, or does it listen to NMEA protocols?

No, only one driver can run on a specific UART. See https://docs.px4.io/master/en/peripherals/serial_configuration.html.

felix-west commented 4 years ago

Ok, so today I looked at the firmware code to see where the incoming messages are being handled and which ones are accepted and which ones are ignored. What I found was under modules/mavlink/mavlink_receiver.cpp. In there I found that the following functions are being used to handle the messages: handle_message_command_long, handle_message_command_int, handle_message_command_ack, handle_message_optical_flow_rad, handle_message_ping, handle_message_set_mode, handle_message_att_pos_mocap, handle_message_set_position_target_local_ned, handle_message_set_position_target_global_int, handle_message_set_attitude_target, handle_message_set_actuator_control_target, handle_message_vision_position_estimate, handle_message_odometry, handle_message_gps_global_origin, handle_message_radio_status, handle_message_manual_control, handle_message_rc_channels_override, handle_message_heartbeat, handle_message_distance_sensor, handle_message_follow_target, handle_message_landing_target, handle_message_adsb_vehicle, handle_message_utm_global_position, handle_message_collision, handle_message_gps_rtcm_data, handle_message_battery_status, handle_message_serial_control, handle_message_logging_ack, handle_message_play_tune, handle_message_obstacle_distance, handle_message_trajectory_representation_waypoints, handle_message_named_value_float, handle_message_debug, handle_message_debug_vect, handle_message_debug_float_array, handle_message_onboard_computer_status, handle_message_statustext

As far as I can tell, there is no message in there to give the raw GPS data in Mavlink format to the FC. Furthermore, it seems to me there is no way to configure it such that the FC either gets raw data from the sensors like it does now but in the form of Mavlink messages, which can be connected directly to Rx and Tx, OR that it gets filtered and processed data which tells it where it is exactly, also in the form of Mavlink.

To me the description sounds like which messages are accepted and processed by the corresponding input. However, I found no documentation as to what these are exactly. How are mode "Normal" and "Onboard" different for example?

It defines the set of outgoing messages, that are continuously streamed.

In other words I have to connect it to QGC and see what messages are streamed between FC and QGC? But it does not change anything in terms of allowed incoming messages?

Does GPS_x_CONFIG allow GPS related Mavlink messages to be accepted, or does it listen to NMEA protocols?

No, only one driver can run on a specific UART. See https://docs.px4.io/master/en/peripherals/serial_configuration.html.

In conjunction with looking at the code of the GPS driver and the Mavlink receiver, it seems to me that the GPS is handled using regular GPS protocols, which would effectively mean that an external device to handle and fuse incoming sensors and gives global position values back to the FC (local positions seem to work using mocap and other messages) using the standard Mavlink library are not handled right now. In this case I can adjust what my stm32 sends to account for this.

stale[bot] commented 4 years ago

This issue has been automatically marked as stale because it has not had recent activity. Thank you for your contributions.