Skip to content

Commit

Permalink
Mavlink protocol in an independent module, solved macro bug
Browse files Browse the repository at this point in the history
  • Loading branch information
xgibert committed Apr 23, 2012
1 parent 1128b8f commit addc54d
Show file tree
Hide file tree
Showing 18 changed files with 140 additions and 93 deletions.
3 changes: 2 additions & 1 deletion conf/airframes/ENAC/fixed-wing/weasel_mavlink.xml
Expand Up @@ -12,6 +12,7 @@
<load name="baro_board.xml"/>
<load name="airspeed_ads1114.xml"/>
<!--load name="mcp355x.xml"/-->
<load name="mavlink.xml"/>
</modules>

<firmware name="fixedwing">
Expand All @@ -31,7 +32,7 @@
<subsystem name="radio_control" type="ppm"/>

<!-- Communication -->
<subsystem name="telemetry" type="mavlink"/>
<subsystem name="telemetry" type="dummy"/>

<!-- Actuators are automatically chosen according to board-->
<subsystem name="imu" type="umarim"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/autopilot/fixedwing.xml
Expand Up @@ -16,7 +16,7 @@

<subsystem name="radio_control" types="ppm"/>
<!-- Communication -->
<subsystem name="telemetry" types="transparent|xbee_api|transparent_usb|mavlink">
<subsystem name="telemetry" types="transparent|xbee_api|transparent_usb|dummy">
<configure name="MODEM_BAUD" values="B9600|B38400|B57600|B115200"/>
</subsystem>
<!-- Actuators (automatically used according to board) -->
Expand Down
11 changes: 11 additions & 0 deletions conf/autopilot/subsystems/fixedwing/telemetry_dummy.makefile
@@ -0,0 +1,11 @@
# Hey Emacs, this is a -*- makefile -*-


ap.CFLAGS += -DUSE_PPRZ_TRANSPORT=0
ap.CFLAGS += -DUSE_$(MODEM_PORT)
ap.CFLAGS += -D$(MODEM_PORT)_BAUD=$(MODEM_BAUD)

ap.CFLAGS += -DDOWNLINK -DDOWNLINK_DEVICE=$(MODEM_PORT) -DDOWNLINK_FBW_DEVICE=$(MODEM_PORT) -DDOWNLINK_AP_DEVICE=$(MODEM_PORT) -DPPRZ_UART=$(MODEM_PORT)
ap.CFLAGS += -DDOWNLINK_TRANSPORT=PprzTransport
ap.srcs += subsystems/datalink/downlink.c subsystems/datalink/pprz_transport.c
ap.srcs += $(SRC_FIRMWARE)/datalink.c
10 changes: 0 additions & 10 deletions conf/autopilot/subsystems/fixedwing/telemetry_mavlink.makefile

This file was deleted.

14 changes: 14 additions & 0 deletions conf/modules/mavlink.xml
@@ -0,0 +1,14 @@
<!DOCTYPE module SYSTEM "module.dtd">

<module name="mavlink">
<header>
<file name="mavlink.h"/>
</header>
<periodic fun="PeriodicSendMavlink(MavlinkTransport, UART1)" freq="60"/>
<event fun="MavlinkDatalinkEvent()"/>
<makefile>
<file name="mavlink.c"/>
<file name="mavlink_transport.c"/>
</makefile>
</module>

31 changes: 0 additions & 31 deletions conf/settings/basic_mavlink.xml

This file was deleted.

3 changes: 2 additions & 1 deletion conf/telemetry/mavlink.xml
@@ -1,7 +1,8 @@
<?xml version="1.0"?>
<!DOCTYPE telemetry SYSTEM "telemetry.dtd">
<telemetry>
<process name="Ap">
<process name="Ap"><mode name="default"/></process>
<process name="Mavlink">
<mode name="default">
<message name="HEARTBEAT" period="5"/>
<!--<message name="SYS_STATUS" period="1"/>
Expand Down
3 changes: 2 additions & 1 deletion sw/airborne/firmwares/fixedwing/ap_downlink.h
Expand Up @@ -66,7 +66,8 @@

#define SEND_MISSION_STATUS(_trans, _dev) Downlink({ \
uint8_t _circle_count = NavCircleCount(); \
DOWNLINK_SEND_MISSION_STATUS(_trans, _dev, &estimator_flight_time, &nav_block, &block_time, &nav_stage, &stage_time, &sys_time.nb_sec, &gps.fix, &dist2_to_wp, &dist2_to_home, &_circle_count, &nav_oval_count, &horizontal_mode);\
uint32_t nb_sec = sys_time.nb_sec; \
DOWNLINK_SEND_MISSION_STATUS(_trans, _dev, &estimator_flight_time, &nav_block, &block_time, &nav_stage, &stage_time, &nb_sec, &gps.fix, &dist2_to_wp, &dist2_to_home, &_circle_count, &nav_oval_count, &horizontal_mode);\
})
/* XGGDEBUG:NEWMESS: if is rotorcraft horizontal_mode should be &guidance_h_mode */

Expand Down
1 change: 0 additions & 1 deletion sw/airborne/firmwares/fixedwing/datalink.c
Expand Up @@ -63,7 +63,6 @@
#include "mcu_periph/uart.h"
#include "subsystems/datalink/downlink.h"
#include "ap_downlink.h"
//#include "mavlink_downlink.h"

#define MOfCm(_x) (((float)(_x))/100.)

Expand Down
28 changes: 28 additions & 0 deletions sw/airborne/modules/mavlink/mavlink.c
@@ -0,0 +1,28 @@
/*
* Paparazzi mcu0 $Id: pprz_transport.c 929 2006-06-02 12:11:37Z poine $
*
* Copyright (C) 2006 Pascal Brisset, Antoine Drouin
* Copyright (C) 2010 ENAC
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*
*/

#define PERIODIC_C_MAVLINK

#include "generated/periodic_telemetry.h"
51 changes: 51 additions & 0 deletions sw/airborne/modules/mavlink/mavlink.h
@@ -0,0 +1,51 @@
/*
* Paparazzi $Id: pprz_transport.h 4870 2010-04-24 03:02:39Z poine $
*
* Copyright (C) 2010 ENAC
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*
*/

/** \file mavlink_transport.h
* \Using MAVLINK protocol
*
*/

#ifndef MAVLINK_H
#define MAVLINK_H

#include "subsystems/datalink/datalink.h"
#include "mavlink_transport.h"

#include "mavlink_downlink.h"

/* Datalink Event */

/*
#define MavlinkDatalinkEvent() { \
MavlinkCheckAndParse(PPRZ_UART, mavlink_tp); \
DlCheckAndParse(); \
}
*/
#define MavlinkDatalinkEvent() {}



#endif /* MAVLINK_H */

Expand Up @@ -22,14 +22,9 @@
*
*/

#include "firmwares/fixedwing/mavlink_downlink.h"
#include "generated/airframe.h"

#ifdef AP
#ifndef TELEMETRY_MODE_AP
#define TELEMETRY_MODE_AP 0
#endif
uint8_t telemetry_mode_Ap_DefaultChannel = TELEMETRY_MODE_AP;
#endif /** AP */

/* PERIODIC_C_MAVLINK is defined before generated/periodic_telemetry.h
* in order to implement telemetry_mode_Mavlink_*
*/
#define PERIODIC_C_MAVLINK

#include "generated/periodic_telemetry.h"
Expand Up @@ -39,40 +39,27 @@

#include "generated/airframe.h"

#ifndef DOWNLINK_DEVICE
#define DOWNLINK_DEVICE DOWNLINK_MAV_DEVICE
#endif
#include "subsystems/datalink/downlink.h"

#include "downlink_msg.h"
#include "generated/periodic.h"

//#include "generated/modules.h"
#include "generated/periodic_telemetry.h"

#if defined DOWNLINK
#define Mavlink(x) x
#else
#define Mavlink(x) {}
#endif


#ifdef AP
/** Telemetry mode for AP process: index in the telemetry.xml file */
#include "ap_downlink.h"
//extern uint8_t telemetry_mode_Ap_DefaultChannel;
#endif

/* _type: 1 for FIXEDWING, 2 for QUADROTOR, 4 for HELICOPTER */
#define PERIODIC_SEND_HEARTBEAT(_trans,_dev) Mavlink ({ \
uint8_t _type = 1; \
uint8_t autopilot = 9; \
uint8_t base_mode = 220; \
uint32_t custom_mode = 0; \
uint8_t system_status = 0; \
uint8_t mavlink_version = 3; \
DOWNLINK_SEND_HEARTBEAT(_trans, _dev, &_type, &autopilot, &base_mode, &custom_mode, &system_status, &mavlink_version); \
})

#define PERIODIC_SEND_HEARTBEAT(_trans,_dev) { \
uint8_t _type = 1;\
uint8_t autopilot = 9;\
uint8_t base_mode = 220;\
uint32_t custom_mode = 0;\
uint8_t system_status = 0;\
uint8_t mavlink_version = 3;\
DOWNLINK_SEND_HEARTBEAT(MavlinkTransport, UART1, &_type, &autopilot, &base_mode, &custom_mode, &system_status, &mavlink_version);\
}

/*
#define PERIODIC_SEND_SYS_STATUS(_trans,_dev) { \
Expand Down
Expand Up @@ -23,10 +23,10 @@
*/

#include <inttypes.h>
#include "subsystems/datalink/mavlink_transport.h"
#include "modules/mavlink/mavlink_transport.h"
#include "mcu_periph/uart.h"

uint8_t ck_a, ck_b, mavlink_down_packet_seq = 1;
uint8_t mavlink_down_packet_seq = 1;
uint16_t checksum;

struct mavlink_transport mavlink_tp;
Expand Up @@ -99,11 +99,11 @@ extern uint16_t checksum;
crc_init(&checksum); \
}

#define MavlinkTransportPutAcId(_dev, _byte) { \ \
#define MavlinkTransportPutAcId(_dev, _byte) { \
MavlinkTransportPut1Byte(_dev, _byte); \
}

#define MavlinkTransportPutUint8(_dev, _byte) { \ \
#define MavlinkTransportPutUint8(_dev, _byte) { \
MavlinkTransportPut1Byte(_dev, _byte); \
crc_accumulate(_byte, &checksum); \
}
Expand Down
8 changes: 0 additions & 8 deletions sw/airborne/subsystems/datalink/datalink.h
Expand Up @@ -47,7 +47,6 @@
/** Datalink kinds */
#define PPRZ 1
#define XBEE 2
#define MAV 3

EXTERN bool_t dl_msg_available;
/** Flag provided to control calls to ::dl_parse_msg. NOT used in this module*/
Expand Down Expand Up @@ -82,13 +81,6 @@ EXTERN void dl_parse_msg(void);
DlCheckAndParse(); \
}

#elif DATALINK == MAV

#define DatalinkEvent() { \
MavlinkCheckAndParse(MAV_UART, mavlink_tp); \
DlCheckAndParse(); \
}

#else

// Unknown DATALINK
Expand Down
2 changes: 0 additions & 2 deletions sw/airborne/subsystems/datalink/downlink.h
Expand Up @@ -40,7 +40,6 @@
#ifdef SIM_UART
#include "sim_uart.h"
#include "subsystems/datalink/pprz_transport.h"
#include "subsystems/datalink/mavlink_transport.h"
#include "subsystems/datalink/xbee.h"
#else /* SIM_UART */
/** Software In The Loop simulation uses IVY bus directly as the transport layer */
Expand All @@ -49,7 +48,6 @@

#else /** SITL */
#include "subsystems/datalink/pprz_transport.h"
#include "subsystems/datalink/mavlink_transport.h"
#include "subsystems/datalink/xbee.h"
#if USE_AUDIO_TELEMETRY
#include "subsystems/datalink/audio_telemetry.h"
Expand Down
10 changes: 10 additions & 0 deletions sw/airborne/subsystems/datalink/pprz_transport.h
Expand Up @@ -53,9 +53,19 @@ extern uint8_t ck_a, ck_b, pprz_down_packet_seq;
/** 4 = STX + len + ck_a + ck_b */
#define PprzTransportSizeOf(_dev, _payload) (_payload+4)

#ifndef USE_PPRZ_TRANSPORT
#define USE_PPRZ_TRANSPORT 1
#endif

#if USE_PPRZ_TRANSPORT
#define PprzTransportCheckFreeSpace(_dev, _x) TransportLink(_dev, CheckFreeSpace(_x))
#define PprzTransportPut1Byte(_dev, _x) TransportLink(_dev, Transmit(_x))
#define PprzTransportSendMessage(_dev) TransportLink(_dev, SendMessage())
#else
#define PprzTransportCheckFreeSpace(_dev, _x) TRUE
#define PprzTransportPut1Byte(_dev, _x) {}
#define PprzTransportSendMessage(_dev) {}
#endif

#define PprzTransportHeader(_dev, payload_len) { \
PprzTransportPut1Byte(_dev, STX); \
Expand Down

0 comments on commit addc54d

Please sign in to comment.