Arduino-Pixhawk Communication via MAVLink: Sending data to Pixhawk?

I apologize if this is the wrong topic to use but I feel like this is most relevant to my issue. If there is a more relevant space to post this feel free to direct me there.

I am trying to send digitized data from an Arduino Mega board to a Pixhawk 1 flight controller using MAVLink. I am following the tutorial posted by Juan Pedro and have read through Pedro Albuquerque’s MAVLink post, linked below:

MAVLink-Arduino Communication Tutorial
MAVLink Step-by-Step

I have followed the tutorial to the best of my ability, and have gotten results back. I am able to read roll and timestamp data from the FC on the Arduino serial monitor. However, when I attempt to send data to the Pixhawk from the Arduino, it does not appear in the MAVLink Inspector on QGroundControl. I have also attempted to log the data and find it after converting to csv, but frankly I have no idea where to begin looking for anything I send to the log. I have attempted to send param_value messages as well as raw_gps_int and data_log messages, but nothing has worked so far. I’ve hesitated to make this post despite being stuck for several days because I know there have been a lot of older posts about this, but I have gone through several of those and none have helped. I would appreciate any feedback or advice anyone would be willing to give. Below is the Arduino IDE code. Thank you.

#include "mavlink.h"
#include "common/mavlink_msg_data_log.h"
int val;
float volt;
int pack;
char cstr[33];
int leds_modo = 1;
int leds_status = 0;
int t1;
unsigned long previousMillisMAVLink = 0;
unsigned long next_interval_MAVLink = 1000;
const int num_hbs = 60;

void setup() {
  // put your setup code here, to run once:
  Serial1.begin(57600);
  Serial.begin(57600);
  Serial.println("Arduino is go!");

}

void loop() {
  // put your main code here, to run repeatedly:
  int sysid = 1;
  int compid = 158;
  int type = MAV_TYPE_QUADROTOR;   ///< 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_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;
  mavlink_message_t msg1;
  uint8_t buf[MAVLINK_MAX_PACKET_LEN];
  uint8_t param_type = 9;
  uint16_t param_count = 2;
  uint16_t param_index = 1;

  //misc test
  int32_t lat = 0;
  int32_t lon = 0;
  //xacc will be test
  int16_t yacc = 0;
  int16_t zacc = 0;
  int16_t xgy = 0;
  int16_t ygy = 0;
  int16_t zgy = 0;
  int16_t xmag = 0;
  int16_t ymag = 0;
  int16_t zmag = 0;
  
  
  val = analogRead(A0);
  volt = (val * 5.00)/1023.00;
  pack = volt * 100;
  itoa(pack, cstr, 10);
  
//CURRENT CONFIGURATION: BOTH HEARTBEAT AND PARAM_VALUE

  //Serial.println(cstr);
  mavlink_msg_heartbeat_pack(1,0, &msg, type, autopilot_type, system_mode, custom_mode, system_state);
  //mavlink_msg_param_value_pack(1,0, &msg, "Voltage", volt, param_type, param_count, param_index);
  //mavlink_msg_data_log_pack(1,0,&msg,volt, 0,0,0,0,0);
  //mavlink_msg_raw_imu_pack(1,0,&msg, t1,pack,yacc,zacc,xgy,ygy,zgy,xmag,ymag,zmag);

  //mavlink_msg_heartbeat_pack(255,0, &msg, type, autopilot_type, system_mode, custom_mode, system_state);
  //mavlink_msg_param_value_pack(1,0, &msg, "Voltage", volt, param_type, param_count, param_index);
  mavlink_msg_data_log_pack(1,155,&msg1,volt, 0,0,0,0,0);
  //mavlink_msg_raw_imu_pack(1,0,&msg, t1,pack,yacc,zacc,xgy,ygy,zgy,xmag,ymag,zmag);
  
  uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
  uint16_t len1 = mavlink_msg_to_send_buffer(buf, &msg1);

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

    Serial1.write(buf, len);
    Serial1.write(buf, len1);
    Serial.println("heart confirmed...");
  }

  //mavlink_msg_heartbeat_pack(255,0, &msg, type, autopilot_type, system_mode, custom_mode, system_state);
  //mavlink_msg_param_value_pack(1,0, &msg, "Voltage", volt, param_type, param_count, param_index);
  mavlink_msg_data_log_pack(255,0,&msg,volt, 0,0,0,0,0);
  //mavlink_msg_raw_imu_pack(1,0,&msg, t1,pack,yacc,zacc,xgy,ygy,zgy,xmag,ymag,zmag);


  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);
    Serial1.write(buf, len);
    Serial.println("data stream active");
  }
}

void comm_receive() {
  mavlink_message_t msg;
  mavlink_status_t status;
  int leds_modo = 0;
  int t;

  while(Serial1.available()>0) {
    uint8_t c = Serial1.read();

    // 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
          }
          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);
          }
          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);
            /*
            char* id = param_value.param_id;
            float val = param_value.param_value;
            uint16_t count = param_value.param_count;
            uint16_t ind = param_value.param_index;
            uint8_t typ = param_value.param_type;
            Serial.println("Paramter info-------------");
            Serial.print("ID: "); Serial.println(id);
            Serial.print("value: "); Serial.println(val);
            Serial.print("count: "); Serial.println(count);
            Serial.print("index: "); Serial.println(ind);
            Serial.print("type: "); Serial.println(typ);
            Serial.println();
            Serial.println();
            */
            
          }
          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;
            t = attitude.time_boot_ms;
          }
          break;

        
       default:
          break;
      }
    }
  }
}

Quick update: I’ve figured out what my mistake was. For anyone who happens to see this, make sure that the system id for your heartbeat signal is the same as the system id for the message you are attempting to send. Feels like a dumb mistake on my part, but at the very least this post may be helpful to another poor undergraduate who is in a similar situation.

3 Likes

Hi Owen,

Thank you for your post. We are trying to use your step-by-step guide to send messages from our Arduino Mega to our Pixhawk. We followed all of the steps you outlined but are running into some difficulties.

We are using your script with a constant value for voltage, and it compiles successfully. However after running your script, we do not see any additional parameters appearing in our QGroundControl software under the “MavLink Inspector” tab.

How is our data supposed to appear within the “MavLink Inspector” tab? Is there a specific variable under which it will appear?

Let us know if there are any additional steps needed to view our data within QGroundControl.

Best,
Gabi