MAVLink and Arduino: step by step

Hello everyone,

My issue is solved, it was a stupid mistake on my side. The break statement between the cases was why I was not getting GPS data continuously. I have one break statement at the end of all the case statements. Now, I get GPS data continuously. Thanks for the help.

My next step is to send a command from Arduino to Cube orange to go to the next waypoint in the mission. Please guide me if anyone has done that before. Thank you again.

Nice work @hemanth_narayan

I’ve successfully used an Arduino to upload a mission of waypoints to my AutoPilot, the code I use is also in my GitHub - pauljeffress/Pulsar-MAVLink-Tester code if that helps.

Let us know how you go.

1 Like

I have a question using the Arduino, is it possible to invert pulse rates if you can get the coding correct? Also how would I find out the pulse rates using the Arduino?

Hi all,
lidar sensor is connected to my orange cube. I have an arduino to integrate it. Depending on the lidar sensor value, (i want to take this message from pixhawk to arduino). Then depending on the rangefinder value checking from the arduino, i want to trigger althold mode to the autopilot( pixhawk).
kindly help me out.

Thanks in advance.

Hello, I have the same problem too. I also tried using a logic level shifter, but it only works if I disconnect the RX. Could you help me, please?

Hi @tudor_MAnole,
Can you describe your setup, how have you wired your Arduino to your autopilot? What port on the autopilot? Can you share the configuration of the port on the autopilot?
Can you share some of your Arduino code?
Thanks,
PJ

Thank you for the response, I am using a FLIGHT CONTROLLER H743-WING V3, I am using Serial Port 3 (http://www.mateksys.com/?portfolio=h743-wing-v2#tab-id-5).
I have the same issue, when the rx is connected, I receive the same msgid repeatedly. After disconnecting it, it enters the mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status) function and then the msgid changes.
I have also tried using a logic level shifter, but the issue remains the same.

Here is my code, it is an sketch for arduino mega beacuse it have more serials:

#include <mavlink.h>

//Mavlink variables
unsigned long previousMillisMAVLink = 0; // will store last time MAVLink was transmitted and listened
unsigned long next_interval_MAVLink = 1000; // next interval to count
const int num_hbs = 2; // # of heartbeats to wait before activating STREAMS from Pixhawk. 60 = one minute.
int num_hbs_pasados = num_hbs;

void setup() {
Serial1.begin(57600); // Mavlink interface start

Serial.begin(57600);
Serial.println(“MAVLink starting.”);
}

void loop() {
int sysid = 1;
int compid = 158;
int type = MAV_TYPE_QUADROTOR;

uint8_t system_type = MAV_TYPE_GENERIC;
uint8_t autopilot_type = MAV_AUTOPILOT_INVALID;

uint8_t system_mode = MAV_MODE_PREFLIGHT; ///< Booting up
uint32_t custom_mode = 0;                 ///< Custom mode, can be defined by user/adopter
uint8_t system_state = MAV_STATE_STANDBY; ///< System ready for flight

mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];


mavlink_msg_heartbeat_pack(1,0, &msg, type,autopilot_type, system_mode, custom_mode, system_state);

uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);

unsigned long currentMillisMAVLink = millis();
if(currentMillisMAVLink - previousMillisMAVLink >= next_interval_MAVLink) {
  previousMillisMAVLink = currentMillisMAVLink;

  Serial1.write(buf, len);


  num_hbs_pasados++;
  if(num_hbs_pasados>=num_hbs) {
    // Request streams from Pixhawk
    Mav_request_Data();
    Serial.println("Streams requested!");
    num_hbs_pasados=0;
  }
}
comm_receive();

}

void Mav_request_Data() {
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
//
const int maxStreams = 2;
const uint8_t MAVStreams[maxStreams] = {MAV_DATA_STREAM_EXTENDED_STATUS, MAV_DATA_STREAM_EXTRA1};
const uint16_t MAVRates[maxStreams] = {0x02, 0x05};
for(int i=0; i<maxStreams; i++){
mavlink_msg_request_data_stream_pack(2, 200, &msg, 1, 0, MAVStreams[i], MAVRates[i], 1);
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);

Serial1.write(buf,len);

}
}

void comm_receive() {
mavlink_message_t msg;
mavlink_status_t status;

while(Serial1.available()>0) {
uint8_t c = Serial1.read();
// Serial.println(c);
// // Serial.println(mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status));
Serial.print(“msgid:”);
Serial.println(msg.msgid);

// Try to get a new message
if(mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status)) {
  Serial.println("here");
  Serial.print("msgid:");
  Serial.println(msg.msgid);
  // Handle message
  switch(msg.msgid) {
    case MAVLINK_MSG_ID_HEARTBEAT:  // #0: Heartbeat
      {
        // E.g. read GCS heartbeat and go into
        // comm lost mode if timer times out
      }
      break;

    case MAVLINK_MSG_ID_SYS_STATUS:  // #1: SYS_STATUS
      {
        /* Message decoding: PRIMITIVE
         *    mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status)
         */
        //mavlink_message_t* msg;
        mavlink_sys_status_t sys_status;
        mavlink_msg_sys_status_decode(&msg, &sys_status);
        Serial.print("PX SYS STATUS: ");
        Serial.print("[Bat (V): ");
        Serial.print(sys_status.voltage_battery);
        Serial.print("], [Bat (A): ");
        Serial.print(sys_status.current_battery);
        Serial.print("], [Comms loss (%): ");
        Serial.print(sys_status.drop_rate_comm);
        Serial.println("]");
      }
      break;

    case MAVLINK_MSG_ID_PARAM_VALUE:  // #22: PARAM_VALUE
      {
        /* Message decoding: PRIMITIVE
         *    mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value)
         */
        //mavlink_message_t* msg;
        mavlink_param_value_t param_value;
        mavlink_msg_param_value_decode(&msg, &param_value);
      }
      break;

    case MAVLINK_MSG_ID_RAW_IMU:  // #27: RAW_IMU
      {
        /* Message decoding: PRIMITIVE
         *    static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu)
         */
        mavlink_raw_imu_t raw_imu;
        mavlink_msg_raw_imu_decode(&msg, &raw_imu);
      }
      break;

    case MAVLINK_MSG_ID_ATTITUDE:  // #30
      {
        /* Message decoding: PRIMITIVE
         *    mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude)
         */
        mavlink_attitude_t attitude;
        mavlink_msg_attitude_decode(&msg, &attitude);

        // if(attitude.roll>1) leds_modo = 0;
        // else if(attitude.roll<-1) leds_modo = 2;
        // else leds_modo=1;
      }
      break;

    
   default:
      break;
  }
}

}
}

Here is the wiring:


And the output of code is nelow:

msgid:0
msgid:0
msgid:0
msgid:0
msgid:0
here
msgid:66
msgid:66
msgid:66
msgid:66
msgid:66
msgid:66
msgid:66
msgid:66
msgid:66
msgid:66
msgid:66
msgid:66
here
msgid:66
In some cases, it returns msgid 4, 9, 114, 115, 32, but very randomly.

Is there any way of making this work over CAN (with a different Arduino Board or an shield), or more likely, I2C??

Small update: I can only read data through Rx and Tx when the flight controller is connected to Mission Planner. Is it possible for to be disabled by default?

Hello, I am trying to get the values of the RC1, RC2…RC7 in real time as I am working on a GUI and a companion computer (Jetson Xavier NX). So my system is as follows:- Futaba receiver is connected to the OrangeCube+ in the RCIN pin and the I use a Gimbal so I have given RC1-RC5 for Gimbal control. The TELEM1 port of the Cube is connected to the Gimbal. TELEM2 is connected to my companion computer using FTDI cables (Serial-USB). I use RC6 and RC7 for my own function for my GUI application, like a trigger when the toggle switch in the RC controller is ON, the GUI performs an action. I need to read the real time values as serial data. How do I do that? I use Mission Planner firmware in my Orangecube+. Is there a discussion thread for interfacing Jetson and MAVLink.

Hi @tudor_MAnole,
Sorry for the delay getting back to you.
It’s hard to check your wiring from those photos, but just make sure you have a really good ground connection between every single component (Arduino MEGA, Level shifter & AutoPilot).
You do need the level shifter as the MEGA is 5v I believe and your AutoPilot is 3.3v.
I’m looking at your code next…standby.
Cheers,
Paul

Hi @tudor_MAnole

I think you have setup the Heartbeat you send to the AutoPilot incorrectly.

In your code you have…

The first two parameters in there are
System_ID
Component_ID
And they should be the SystemID and the ComponentID of your Arduino board.
So you should use the variables you setup for that already. I can see them in your code

So the whole command would be

mavlink_msg_heartbeat_pack(sysid, compid, &msg, type,autopilot_type, system_mode, custom_mode, system_state);

Try that, and see if that helps first.
Good Luck,
Paul

Hi again.
In the above screenshot you posted, it looks like you are selecting MAVLink version 2. Are you using the MAVLink v2 library (mavlink.h) files?

Also,

In this line in your code, you also need to correctly set the source (your Arduino board) and destination (your AutoPilot) SystemID and ComponentIDs.

So yours should be something like;

mavlink_msg_request_data_stream_pack(sysid, compid, &msg, 1, 1, MAVStreams[i], MAVRates[i], 1);

Let me know how that goes, I think this will help a lot.

Also I have a lot of sample code you can check at GitHub - pauljeffress/Pulsar-MAVLink-Tester
That you can take bits from.

Did you find out why there is the Comp0 Mav_comp_id_all? Im having exactly the same problem with serial3, did you figure it out?? Any help would be extremely helpful.

Only one of 3 boards i have tried have the comp0 and comp1,

Hi @ddomit,
I’m not sure what @cges ended up doing to fix their issue.
What do you mean by

Only one of 3 boards i have tried have the comp0 and comp1,

Is that three different AutopIlots boards? And if so, what are they.
I noticed my OrangeCube AutoPilot emits MAVLink messages from both sysID=1, CompID=0 AND sysID=1, CompID=1. I can’t remember exactly but one was the main Autopilot component and the other was the ADSB module that is also in the Orange Cube. Both send HEARTBEAT MAVLink messages.

Another good general tip to help with troubleshooting MAVLink between an AutoPilot and an Arduino board is to use a separate Arduino running simply as a “listener”.
You connect the listener Arduino’s RX (leave its TX disconnected) to either the TX of your main Arduino or the RX of your main Arduino, depending on which traffic you are trying to inspect. You must also connect the listener Arduino Ground to the same Ground as the main Arduino. Then on the listener Arduino run the GitHub - pauljeffress/Pulsar-MAVLink-Tester code and just watch what MAVLink a device is sending.

Thanks Paul!

Im actually connecting a camera that takes gps inputs from this port.

I already seti it up in two CubeOrgange on serial 3, the problem im having is on CubeOrange+.

Both comp ID are from vehicle one, but compID=0 only sends heartbeat and compID=1 sends all normal mavlink data. I suspect the camera is trying to get GPS coordinates from the first CompID??

Thats all i can think of, thats why i want to try to disable the compID=0 to test if that is the problem.

Hey @ddomit I think this might be a question for the CubeOrange+ vendor cubepilot.org.

1 Like


Hello everyone,
I’m trying to access pixhawk data via arduino with Mavlink but I couldn’t succeed. I tried many examples but pixhawk doesn’t send me data (or I can’t receive it). You can see my connections in the photos I shared. The code block I used:

/* MAVLInk_DroneLights
 *  by Juan Pedro López
 *  
 * This program was developed to connect an Arduino board with a Pixhawk via MAVLink 
 *   with the objective of controlling a group of WS2812B LED lights on board of a quad
 * 
 * The current version of the program is working properly.
 * 
 * TO DO:
 *  - Move STREAMS request to RC_CHANNELS to use values in logic
 *  - Add RC_CHANNLES_RAW messages monitoring: move #30 to RC_CHANNELS_RAW (#35)
 *      http://mavlink.org/messages/common#RC_CHANNELS_RAW
 *  - Look for message on low battery:
 *      To be tested: http://mavlink.org/messages/common#PARAM_REQUEST_READ
 *      To be checked: http://mavlink.org/messages/common#SYS_STATUS
 *  - Potential implementation of other alarms, like high intensity
 *      
 * You can restrict the maximum package size with this parameter in mavlink_types.h:

    #ifndef MAVLINK_MAX_PAYLOAD_LEN_
    // it is possible to override this, but be careful! Defa_
    #define **MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length_
    #endif_
 */


// In case we need a second serial port for debugging

  // Library to use serial debugging with a second board


#include "mavlink.h"
//#include "common/mavlink_msg_request_data_stream.h"


// Mavlink variables
unsigned long previousMillisMAVLink = 0;     // will store last time MAVLink was transmitted and listened
unsigned long next_interval_MAVLink = 1000;  // next interval to count
const int num_hbs = 60;                      // # of heartbeats to wait before activating STREAMS from Pixhawk. 60 = one minute.
int num_hbs_pasados = num_hbs;

// Lights flashing adjustment
unsigned long previousMillis = 0;     // will store last time LED was updated
unsigned long next_interval = 0;      // next interval
const long tiempo_on = 20;
const long tiempo_off = 80;
const long tiempo_descanso = 880;
int test_led_tipo = 4;
#define SOFT_SERIAL_DEBUGGING   // Comment this line if no serial debugging is needed
#ifdef SOFT_SERIAL_DEBUGGING
  // Library to use serial debugging with a second board
  #include <SoftwareSerial.h>
  SoftwareSerial pxSerial(9,10);   // RX, TX
#endif

void setup() {
  // MAVLink interface start
  Serial.begin(57600);
  #ifdef SOFT_SERIAL_DEBUGGING
  // [DEB] Soft serial port start
  Serial.begin(57600);
  Serial.println("MAVLink starting.");
  pxSerial.begin(115200);
#endif
}

void loop() {
  // Lights management
  // Light pulses: 2 quick flashes per second. 100 ms each cycle
  unsigned long currentMillis = millis();
  int i=0;

        
  // MAVLink
  /* The default UART header for your MCU */ 
  int sysid = 1;                   ///< ID 20 for this airplane. 1 PX, 255 ground station
  int compid = 158;                ///< The component sending the message
  int type = MAV_TYPE_FIXED_WING;   ///< This system is an airplane / fixed wing
 
  // Define the system type, in this case an airplane -> on-board controller
  // uint8_t system_type = MAV_TYPE_FIXED_WING;
  uint8_t system_type = MAV_TYPE_GENERIC;
  uint8_t autopilot_type = MAV_AUTOPILOT_INVALID;
 
  uint8_t system_mode = MAV_MODE_PREFLIGHT; ///< Booting up
  uint32_t custom_mode = 0;                 ///< Custom mode, can be defined by user/adopter
  uint8_t system_state = MAV_STATE_STANDBY; ///< System ready for flight
  // Initialize the required buffers
  mavlink_message_t msg;
  uint8_t buf[MAVLINK_MAX_PACKET_LEN];
 
  // Pack the message
  //mavlink_msg_heartbeat_pack(sysid,compid, &msg, type, autopilot_type, system_mode, custom_mode, system_state);
  mavlink_msg_heartbeat_pack(1,0, &msg, type, autopilot_type, system_mode, custom_mode, system_state);
 
  // Copy the message to the send buffer
  uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
 
  // Send the message with the standard UART send function
  // uart0_send might be named differently depending on
  // the individual microcontroller / library in use.
  unsigned long currentMillisMAVLink = millis();
  if (currentMillisMAVLink - previousMillisMAVLink >= next_interval_MAVLink) {
    // Guardamos la última vez que se cambió el modo
    previousMillisMAVLink = currentMillisMAVLink;

#ifdef SOFT_SERIAL_DEBUGGING
    pxSerial.write(buf,len);
    //Serial.println("Ardu HB");
#else
    Serial.write(buf, len);
#endif

    //Mav_Request_Data();
    num_hbs_pasados++;
    if(num_hbs_pasados>=num_hbs) {
      // Request streams from Pixhawk
#ifdef SOFT_SERIAL_DEBUGGING
      Serial.println("Streams requested!");
#endif
      Mav_Request_Data();
      num_hbs_pasados=0;
    }

  }

  // Check reception buffer
  comm_receive();
}

void Mav_Request_Data()
{
  mavlink_message_t msg;
  uint8_t buf[MAVLINK_MAX_PACKET_LEN];


  // STREAMS that can be requested
  /*
   * Definitions are in common.h: enum MAV_DATA_STREAM
   *   
   * MAV_DATA_STREAM_ALL=0, // Enable all data streams
   * MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.
   * MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS
   * MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW
   * MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.
   * MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.
   * MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot
   * MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot
   * MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot
   * MAV_DATA_STREAM_ENUM_END=13,
   * 
   * Data in PixHawk available in:
   *  - Battery, amperage and voltage (SYS_STATUS) in MAV_DATA_STREAM_EXTENDED_STATUS
   *  - Gyro info (IMU_SCALED) in MAV_DATA_STREAM_EXTRA1
   */

  // To be setup according to the needed information to be requested from the Pixhawk
  const int  maxStreams = 2;
  const uint8_t MAVStreams[maxStreams] = {MAV_DATA_STREAM_EXTENDED_STATUS, MAV_DATA_STREAM_EXTRA1};
  const uint16_t MAVRates[maxStreams] = {0x02,0x05};

    
  for (int i=0; i < maxStreams; i++) {
    /*
     * mavlink_msg_request_data_stream_pack(system_id, component_id, 
     *    &msg, 
     *    target_system, target_component, 
     *    MAV_DATA_STREAM_POSITION, 10000000, 1);
     *    
     * mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, 
     *    mavlink_message_t* msg,
     *    uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, 
     *    uint16_t req_message_rate, uint8_t start_stop)
     * 
     */
    mavlink_msg_request_data_stream_pack(2, 200, &msg, 1, 0, MAVStreams[i], MAVRates[i], 1);
    uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
#ifdef SOFT_SERIAL_DEBUGGING
    pxSerial.write(buf,len);
#else
    Serial.write(buf, len);
#endif
  }
  
  // Request: PARAM_REQUEST_LIST. Only for full log recording
  /*
   * Primitive: mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
                   uint8_t target_system, uint8_t target_component)
   */
/*
  // Configure
  uint8_t system_id=2;
  uint8_t component_id=200;
  // mavlink_message_t* msg;
  uint8_t target_system=1;
  uint8_t target_component=0;

  // Pack
  mavlink_msg_param_request_list_pack(system_id, component_id, &msg,
    target_system, target_component);
  uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);

  // Send
#ifdef SOFT_SERIAL_DEBUGGING
    pxSerial.write(buf,len);
#else
    Serial.write(buf, len);
#endif
*/
}



void comm_receive() {
 
  mavlink_message_t msg;
  mavlink_status_t status;
 
  // Echo for manual debugging
  // Serial.println("---Start---");

#ifdef SOFT_SERIAL_DEBUGGING
  while(pxSerial.available()>0) {
    uint8_t c = pxSerial.read();
#else
  while(Serial.available()>0) {
    uint8_t c = Serial.read();
#endif

    // Try to get a new message
    if(mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status)) {

      // Handle message
      switch(msg.msgid) {
        case MAVLINK_MSG_ID_HEARTBEAT:  // #0: Heartbeat
          {
            // E.g. read GCS heartbeat and go into
            // comm lost mode if timer times out
#ifdef SOFT_SERIAL_DEBUGGING
            //Serial.println("PX HB");
#endif
          }
          break;

        case MAVLINK_MSG_ID_SYS_STATUS:  // #1: SYS_STATUS
          {
            /* Message decoding: PRIMITIVE
             *    mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status)
             */
            //mavlink_message_t* msg;
            mavlink_sys_status_t sys_status;
            mavlink_msg_sys_status_decode(&msg, &sys_status);
#ifdef SOFT_SERIAL_DEBUGGING
            Serial.print("PX SYS STATUS: ");
            Serial.print("[Bat (V): ");
            Serial.print(sys_status.voltage_battery);
            Serial.print("], [Bat (A): ");
            Serial.print(sys_status.current_battery);
            Serial.print("], [Comms loss (%): ");
            Serial.print(sys_status.drop_rate_comm);
            Serial.println("]");
#endif
          }
          break;

        case MAVLINK_MSG_ID_PARAM_VALUE:  // #22: PARAM_VALUE
          {
            /* Message decoding: PRIMITIVE
             *    mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value)
             */
            //mavlink_message_t* msg;
            mavlink_param_value_t param_value;
            mavlink_msg_param_value_decode(&msg, &param_value);
#ifdef SOFT_SERIAL_DEBUGGING
            Serial.println("PX PARAM_VALUE");
            Serial.println(param_value.param_value);
            Serial.println(param_value.param_count);
            Serial.println(param_value.param_index);
            Serial.println(param_value.param_id);
            Serial.println(param_value.param_type);
            Serial.println("------ Fin -------");
#endif
          }
          break;

        case MAVLINK_MSG_ID_RAW_IMU:  // #27: RAW_IMU
          {
            /* Message decoding: PRIMITIVE
             *    static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu)
             */
            mavlink_raw_imu_t raw_imu;
            mavlink_msg_raw_imu_decode(&msg, &raw_imu);
#ifdef SOFT_SERIAL_DEBUGGING
            //Serial.println("PX RAW IMU");
            //Serial.println(raw_imu.xacc);
#endif
          }
          break;

        case MAVLINK_MSG_ID_ATTITUDE:  // #30
          {
            /* Message decoding: PRIMITIVE
             *    mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude)
             */
            mavlink_attitude_t attitude;
            mavlink_msg_attitude_decode(&msg, &attitude);
#ifdef SOFT_SERIAL_DEBUGGING
            //Serial.println("PX ATTITUDE");
            //Serial.println(attitude.roll);
            Serial.println("asd");

#endif
          }
          break;

        
       default:
#ifdef SOFT_SERIAL_DEBUGGING
          Serial.print("--- Otros: ");
          Serial.print("[ID: ");
          Serial.print(msg.msgid);
          Serial.print("], [seq: ");
          Serial.print(msg.seq);
          Serial.println("]");
#endif
          break;
      }
    }
  }
}

As you can see, it constantly outputs “Stream Requested!”. I think pixhawk is not sending data.
Please help me.
Sincerely.

Hi @Ufuk_Beydemir,

I think I can see the issue. In the following line in your code

You are setting the serial port that you have connected to your autopilot to 115200bps, whereas it should be 57000bps. Unless you have changed the corresponding configuration on your autopilot?

Also I do not find SoftwareSerial very reliable and as you are using an Arduino Mega board, you have four hardware serial ports to use, so you do not need SoftwareSerial.

Connect your autopilot to Tx2/RX2 and use Serial2.begin(57600);
And replace “pxSerial” with “Serial2” in your code and you should be in better shape.

That’s the first stuff I would try.

Good luck and let us know how you go.

Cheers,
Paul