Difference between revisions of "DevGuide/CommunicationsNew"
m |
m |
||
Line 5: | Line 5: | ||
[[Messages_Format_New|Messages_Format]] | [[Messages_Format_New|Messages_Format]] | ||
We'll start with high level stuff such as sending your own telemetry message or | We'll start with high level stuff such as sending your own telemetry message or command (uplink) message. We'll then look at the lower layers | ||
== Sending telemetry message == | == Sending telemetry message == | ||
Revision as of 01:10, 4 May 2012
!THIS NEW COMMUNICATION SYSTEM IS NOT AVAILABLE YET
This page describes the way the communications with the aircrafts are implemented in paparazzi.
We'll start with high level stuff such as sending your own telemetry message or command (uplink) message. We'll then look at the lower layers
Sending telemetry message
Describe your message in one of the the downlink or datalink type classes, all the classes are allocated in different xml files inside the folder conf/messages. e.g. conf/messages/custom_downlink.xml
This should look like this
<message name="MARK" id="32"> <field name="ac_id" type="uint8"/> <field name="lat" type="float" unit="deg"/> <field name="long" type="float" unit="deg"/> <field name="alt" type="uint32" unit="mm" alt_unit="m" alt_unit_coef="1000"/> </message>
The id has to be unique for each class. The fields can have type int8, int16, int32, int64, uint8, uint16, uint32, uint64, float, char and arrays of those. They must be aligned on a multiple of their size (c.f. examples with pad fields) (ALIGNMENT ONLY FOR UPLINK/DATALINK MESSAGES). The arrays can be with fixed or variable length:
- Fixed: (e.g. uint16[13]) You can use as many fixed length arrays as you want. They have to be aligned taking in mind that they don't have a preceding length byte. - Variable: (e.g. uint16[]) You can use only one variable length array and it must be the last field. It has to be aligned taking in mind that it has a preceding length byte.
The alt_unit and alt_unit_coef will be used the Plotter and the Messages agents to display human readable values. When alt_unit_coef is not specified, some basic default conversions are automatic:
- deg <-> rad
- deg/s <-> rad/s
- m <-> cm
- m/s <-> cm/s
- decideg -> deg
This enables all the ground system to deal with your message and generate sending code for the airborne system. The code is generated in var/include/messages_<class_name>.h.
From the airborne code you can send the message by using this code, for example
DOWNLINK_SEND_MARK(DefaultChannel, &mark_id, &mark_lat, &mark_long, &mark_alt);
The first parameter of the DOWNLINK_SEND_x macro is the channel you want to send it over, in most cases you want to use the DefaultChannel.
You can also have the autopilot send the message periodically. For doing so, in your telemetry file (for example conf/telemetry/default.xml, you can make your own and reference it in the conf/conf.xml file). You can add a line like
<message name="MARK" period="1"/>
meaning that MARK will be sent every second. You then need to specify the arguments to your message in the sw/airborne/firmwares/fixedwing/ap_downlink.h or sw/airborne/firmwares/rotorcraft/telemetry.h header by providing a macro
#define PERIODIC_SEND_MARK() DOWNLINK_SEND_MARK(DefaultChannel, &mark_id, &mark_lat, &mark_long, &mark_alt)
You can have different telemetry modes having different rates for each message. For example you might want a verbose mode and a stealth mode.
When sent by the aircraft the message will be available on the ground ivy bus. You can watch it using the messages program or with the ivyprobe command line ( ivyprobe '(.*)' ).
The file sw/ground_segment/cockpit/ant_track.c shows how to receive a message in a C program. For ocaml, we have a higher level library to receive messages (sw/lib/ocaml/pprz.ml).
Adding uplink messages
This is similar to the above. Add your message in one of the datalink or uplink classes in conf/messages/ This will generate parsing code for the airborne program (var/include/messages_<class_name>.h).
There are several possibilities to parse the uplink messages:
- add your handler in the sw/airborne/firmwares/fixedwing/datalink.c or sw/airborne/firmwares/rotorcraft/datalink.c code
- use a module with a datalink node where you specify the message to be parsed and the function to be called when the messages arrives
- or you can just rewrite your own dl_parse_msg() function, for example in a test program where you want to receive only your own messages.
Selecting desired message classes
To select which message classes Paparazzi is going to use you have to include them in conf/messages_conf.xml. If this file doesn't exist Paparazzi will make a copy of conf/messages_conf.xml.example. To create a new class you can create a new xml file in conf/messages/ and then include it in the previous file. The class file must include the class type:
- downlink: classes to send messages from the A/C to ground. - uplink: classes to send messages from ground to the A/C. Fields alignment will be checked. - datalink: classes with messages that can be used both ways. Fields alignment will be checked. - airborne: classes to comunicate between components in the airborne. !CHECKING NOT IMPLEMENTED - ground: classes to comunicate between components in ground segment.
The "transport" layer
Paparazzi can use the built-in transport layer of different hardware (currently only wavecards and xbee/xtends) and also provides his own layer for hardware lacking it (showing as remote serial ports). C sourcecode (.c) and belonging header (.h) -files are: xbee.c, xbee.h and pprz_transport.c, pprz_transport.h
Mavlink compatibility
! The procedure descrived a continuation makes the communication only compatible with Mavlink QGroundControl, not Paparazzi Center.
To use Mavlink protocol and messages we have to follow these steps:
1- Change the telemetry protocol in the airframe file to "dummy". This will disable paparazzi protocol to avoid sending messages like PPRZ_MODE. 2- Add "mavlink" module in the airframe file. This module includes periodic Mavlink messages implementation and Mavlink protocol to send them. 3- Change the telemetry file: deleting all messages inside Ap process and adding a Mavlink process including only Mavlink messages. (e.g. mavlink.xml) Note that message names that are already used by Paparazzi are renamed to MAVLINK_<old message name> e.g. MAVLINK_ATTITUDE.
Mavlink generator computes CRC_EXTRA for each message from its fields. Then it resort the fields with inverse field length order to generate the macros. To use Mavlink messages in Paparazzi the messages must be defined with the already sorted fields in the XML file. The CRC_EXTRA values are hard-coded in mavlink_protocol.c, located in sw/airborne/modules/mavlink/, and they must be updated manually after every change in message definitions. The file to implement periodic mavlink messages is mavlink_downlink.h located in sw/airborne/modules/mavlink/
Video showing Paparazzi working with QGroundControl, a ground station software that uses Mavlink protocol: Watch video