Skip to content

Commit

Permalink
switch mavlink library
Browse files Browse the repository at this point in the history
  • Loading branch information
d3ngit committed Jan 6, 2020
1 parent eb4e0dd commit c4e4f56
Show file tree
Hide file tree
Showing 738 changed files with 205,593 additions and 20,577 deletions.
50 changes: 50 additions & 0 deletions Arduino_libraries/GCS_MAVLink/GCS_MAVLink.cpp
@@ -0,0 +1,50 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-

/// @file GCS_MAVLink.cpp

/*
This provides some support code and variables for MAVLink enabled sketches
This firmware is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
*/

//#include <FastSerial.h>
//#include <AP_Common.h>
#include <GCS_MAVLink.h>


Stream *mavlink_comm_0_port;
Stream *mavlink_comm_1_port;

mavlink_system_t mavlink_system = {12,1,0,0}; //modified

uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
{
if (sysid != mavlink_system.sysid)
return 1;
// Currently we are not checking for correct compid since APM is not passing mavlink info to any subsystem
// If it is addressed to our system ID we assume it is for us
return 0; // no error
}

/*
// return a MAVLink variable type given a AP_Param type
uint8_t mav_var_type(enum ap_var_type t)
{
if (t == AP_PARAM_INT8) {
return MAVLINK_TYPE_INT8_T;
}
if (t == AP_PARAM_INT16) {
return MAVLINK_TYPE_INT16_T;
}
if (t == AP_PARAM_INT32) {
return MAVLINK_TYPE_INT32_T;
}
// treat any others as float
return MAVLINK_TYPE_FLOAT;
}
*/
126 changes: 126 additions & 0 deletions Arduino_libraries/GCS_MAVLink/GCS_MAVLink.h
@@ -0,0 +1,126 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-

/// @file GCS_MAVLink.h
/// @brief One size fits all header for MAVLink integration.

#ifndef GCS_MAVLink_h
#define GCS_MAVLink_h

#include <Stream.h>


//#include <BetterStream.h>

// we have separate helpers disabled to make it possible
// to select MAVLink 1.0 in the arduino GUI build
//#define MAVLINK_SEPARATE_HELPERS

#include "include/mavlink/v1.0/ardupilotmega/version.h"

// this allows us to make mavlink_message_t much smaller
#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE

#define MAVLINK_COMM_NUM_BUFFERS 1
#include "include/mavlink/v1.0/mavlink_types.h"

/// MAVLink stream used for HIL interaction
extern Stream *mavlink_comm_0_port;

/// MAVLink stream used for ground control communication
extern Stream *mavlink_comm_1_port;

/// MAVLink system definition
extern mavlink_system_t mavlink_system;

/// Send a byte to the nominated MAVLink channel
///
/// @param chan Channel to send to
/// @param ch Byte to send
///
static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
{
switch(chan) {
case MAVLINK_COMM_0:
mavlink_comm_0_port->write(ch);
break;
case MAVLINK_COMM_1:
mavlink_comm_1_port->write(ch);
break;
default:
break;
}
}

/// Read a byte from the nominated MAVLink channel
///
/// @param chan Channel to receive on
/// @returns Byte read
///
static inline uint8_t comm_receive_ch(mavlink_channel_t chan)
{
uint8_t data = 0;

switch(chan) {
case MAVLINK_COMM_0:
data = mavlink_comm_0_port->read();
break;
case MAVLINK_COMM_1:
data = mavlink_comm_1_port->read();
break;
default:
break;
}
return data;
}

/// Check for available data on the nominated MAVLink channel
///
/// @param chan Channel to check
/// @returns Number of bytes available
static inline uint16_t comm_get_available(mavlink_channel_t chan)
{
uint16_t bytes = 0;
switch(chan) {
case MAVLINK_COMM_0:
bytes = mavlink_comm_0_port->available();
break;
case MAVLINK_COMM_1:
bytes = mavlink_comm_1_port->available();
break;
default:
break;
}
return bytes;
}


/// Check for available transmit space on the nominated MAVLink channel
///
/// @param chan Channel to check
/// @returns Number of bytes available, -1 for error
static inline int comm_get_txspace(mavlink_channel_t chan)
{
switch(chan) {
case MAVLINK_COMM_0:
// return mavlink_comm_0_port->txspace();
return 65535;
break;
case MAVLINK_COMM_1:
//return mavlink_comm_1_port->txspace();
return 65535;
break;
default:
break;
}
return -1;
}

#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
#include "include/mavlink/v1.0/ardupilotmega/mavlink.h"

uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid);

// return a MAVLink variable type given a AP_Param type
//uint8_t mav_var_type(enum ap_var_type t);

#endif // GCS_MAVLink_h
20 changes: 20 additions & 0 deletions Arduino_libraries/GCS_MAVLink/generate.sh
@@ -0,0 +1,20 @@
#!/bin/sh
# script to re-generate mavlink C code for APM

mavdir="$(dirname $0)"
dname="$(basename $mavdir)"
[ "$dname" = "GCS_MAVLink" ] || {
echo "This script should be run from the libraries/GCS_MAVLink directory"
exit 1
}

if ! which mavgen.py > /dev/null; then
echo "mavgen.py must be in your PATH. Get it from http://github.com/mavlink/mavlink in the pymavlink/generator directory"
exit 1
fi

echo "Removing old includes"
rm -rf "$mavdir/include/*"

echo "Generating C code"
mavgen.py --lang=C --wire-protocol=1.0 --output=$mavdir/include/mavlink/v1.0 $mavdir/message_definitions/ardupilotmega.xml

0 comments on commit c4e4f56

Please sign in to comment.