Skip to content

Update at.c #1

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 25 commits into
base: SiK
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
a5740ee
atcommander: initial commit
May 15, 2014
85c5f52
Fixed out of sync definitions for set_frequency_registers() and scale…
LorenzMeier Aug 10, 2014
02be23f
Fixed out of sync definitions for set_frequency_registers() and scale…
LorenzMeier Aug 10, 2014
1c54590
Update URL: change from google code to wordpress wiki
Mar 17, 2015
35815a6
pattern.py: added randlength option and reopen
Dec 4, 2014
c264c67
tdm: fixed LDB_RSSI on initial set
tridge Oct 17, 2015
1d1da0c
Adding segment rules for those wanting to play with banking support
lhovo Nov 21, 2015
e9557ef
Update at.c
OpenUAS Nov 24, 2015
63d34ca
Merge pull request #21 from LorenzMeier/master
LorenzMeier Apr 25, 2016
145ce80
support newer pyserial for setBaudRate
tridge May 16, 2016
cc004ab
simple script for binary data testing
tridge May 23, 2016
814e580
mavtester: added MAVLink2 support
tridge May 23, 2016
95f8273
mavtester: handle RADIO packets
tridge May 23, 2016
3e4f55d
added support for MAVLink2
tridge May 23, 2016
d8a217b
removed swap_bytes
tridge May 25, 2016
1b9845a
raise version to 2.0
tridge May 26, 2016
38111e6
Merge branch 'RFDesign_SIK'
tridge May 31, 2016
d2031a0
at: fixed ati5 output
tridge Jun 5, 2016
74fa770
Made the port parameter mandatory in the parser
gmorph Jun 5, 2016
1b2988b
remove unused variables
tridge Jun 27, 2016
050b5c1
tools: improved mavtester.py
tridge Jul 29, 2016
c738ae5
cleanup unused code
tridge Aug 4, 2016
48faed2
a 3-way version of mavtester
tridge Aug 4, 2016
67ccede
Port fix
makeoneupforme Feb 2, 2017
0f599f6
Merge other modifications
makeoneupforme Feb 2, 2017
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions Firmware/radio/at.c
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ at_timer(void)
at_cmd_ready = true;
break;
default:
// should never happen, but otherwise harmless
; // should never happen, but otherwise harmless
}
}
}
Expand Down Expand Up @@ -339,7 +339,7 @@ at_i(void)
printf("%u\n", g_board_bl_version);
return;
case '5':
print_ID_vals(' ', PARAM_MAX, param_name, param_get);
print_ID_vals('S', PARAM_MAX, param_name, param_get);
return;
case '6':
tdm_report_timing();
Expand Down
2 changes: 0 additions & 2 deletions Firmware/radio/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,6 @@ __pdata struct statistics statistics, remote_statistics;

/// optional features
bool feature_golay;
bool feature_opportunistic_resend;
uint8_t feature_mavlink_framing;
bool feature_rtscts;

Expand All @@ -121,7 +120,6 @@ main(void)

// setup boolean features
feature_mavlink_framing = param_get(PARAM_MAVLINK);
feature_opportunistic_resend = param_get(PARAM_OPPRESEND)?true:false;
feature_golay = param_get(PARAM_ECC)?true:false;
feature_rtscts = param_get(PARAM_RTSCTS)?true:false;

Expand Down
41 changes: 9 additions & 32 deletions Firmware/radio/mavlink.c
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,6 @@
extern __xdata uint8_t pbuf[MAX_PACKET_LENGTH];
static __pdata uint8_t seqnum;

#define MAVLINK_MSG_ID_RADIO 166
#define MAVLINK_RADIO_CRC_EXTRA 21

// new RADIO_STATUS common message
#define MAVLINK_MSG_ID_RADIO_STATUS 109
#define MAVLINK_RADIO_STATUS_CRC_EXTRA 185
Expand Down Expand Up @@ -112,17 +109,8 @@ struct mavlink_RADIO_v10 {
uint8_t remnoise;
};

static void swap_bytes(__pdata uint8_t ofs, __pdata uint8_t len)
{
register uint8_t i;
for (i=ofs; i<ofs+len; i+=2) {
register uint8_t tmp = pbuf[i];
pbuf[i] = pbuf[i+1];
pbuf[i+1] = tmp;
}
}

/// send a MAVLink status report packet
/// we always send as MAVLink1 and let the recipient sort it out.
void MAVLink_report(void)
{
struct mavlink_RADIO_v10 *m = (struct mavlink_RADIO_v10 *)&pbuf[6];
Expand All @@ -131,26 +119,15 @@ void MAVLink_report(void)
pbuf[2] = seqnum++;
pbuf[3] = RADIO_SOURCE_SYSTEM;
pbuf[4] = RADIO_SOURCE_COMPONENT;
pbuf[5] = MAVLINK_MSG_ID_RADIO;

m->rxerrors = errors.rx_errors;
m->fixed = errors.corrected_packets;
m->txbuf = serial_read_space();
m->rssi = statistics.average_rssi;
m->remrssi = remote_statistics.average_rssi;
m->noise = statistics.average_noise;
m->remnoise = remote_statistics.average_noise;
mavlink_crc(MAVLINK_RADIO_CRC_EXTRA);

if (serial_write_space() < sizeof(struct mavlink_RADIO_v10)+8) {
// don't cause an overflow
return;
}

serial_write_buf(pbuf, sizeof(struct mavlink_RADIO_v10)+8);

// now the new RADIO_STATUS common message
pbuf[5] = MAVLINK_MSG_ID_RADIO_STATUS;

m->rxerrors = errors.rx_errors;
m->fixed = errors.corrected_packets;
m->txbuf = serial_read_space();
m->rssi = statistics.average_rssi;
m->remrssi = remote_statistics.average_rssi;
m->noise = statistics.average_noise;
m->remnoise = remote_statistics.average_noise;
mavlink_crc(MAVLINK_RADIO_STATUS_CRC_EXTRA);

if (serial_write_space() < sizeof(struct mavlink_RADIO_v10)+8) {
Expand Down
128 changes: 39 additions & 89 deletions Firmware/radio/packet.c
Original file line number Diff line number Diff line change
Expand Up @@ -80,56 +80,16 @@ bool seen_mavlink;
// monitoring of link quality
static void check_heartbeat(__xdata uint8_t * __pdata buf)
{
if (buf[0] == MAVLINK10_STX &&
buf[1] == 9 && buf[5] == 0) {
// looks like a MAVLink 1.0 heartbeat
if ((buf[1] == 9 && buf[0] == MAVLINK10_STX && buf[5] == 0) ||
(buf[1] <= 9 && buf[0] == MAVLINK20_STX && buf[7] == 0 && buf[8] == 0 && buf[9] == 0)) {
// looks like a MAVLink heartbeat
seen_mavlink = true;
}
}

#define MSG_TYP_RC_OVERRIDE 70
#define MSG_LEN_RC_OVERRIDE (9 * 2)

/// Return the offset of any high priority packet (so we can ensure that this packet goes out in the next
/// tx window
static
int16_t extract_hipri(uint8_t max_xmit)
{
__xdata uint16_t slen = serial_read_available();
__xdata uint16_t offset = 0;
__xdata int16_t high_offset = -1;

// Walk the serial buffer to find the _last_ high pri packet
while (slen >= 8) {
register uint8_t c = serial_peekx(offset);
if (c != MAVLINK10_STX) {
// we've lost mavlink framing - stop scanning for this window
break;
}
c = serial_peekx(offset + 1);
if (c >= 255 - 8 ||
c+8 > max_xmit - last_sent_len) {
// it won't fit
break;
}
if (c+8 > slen) {
// we don't have the full MAVLink packet in
// the serial buffer
break;
}

if(serial_peekx(offset + 5) == MSG_TYP_RC_OVERRIDE && c == MSG_LEN_RC_OVERRIDE) {
// if(high_offset != -1) printf("found 2nd\r\n"); else printf("found rc\r\n");
high_offset = offset;
}

c += 8;
slen -= c;
offset += c;
}

return high_offset;
}

#define MAVLINK_FRAMING_DISABLED 0
#define MAVLINK_FRAMING_SIMPLE 1
Expand All @@ -140,65 +100,52 @@ int16_t extract_hipri(uint8_t max_xmit)
static
uint8_t mavlink_frame(uint8_t max_xmit, __xdata uint8_t * __pdata buf)
{
__data uint16_t slen, offset = 0, high_offset;
__data uint16_t slen;

//
// There is already a packet sitting waiting here
//
// but this optimization is redundant with the loop below. By letting the very slightly
// more expensive version its thing we can ensure we skip _all_ redundant rc_override msgs
#if 0
serial_read_buf(last_sent, mav_pkt_len);
last_sent_len = mav_pkt_len;
memcpy(buf, last_sent, last_sent_len);
check_heartbeat(buf);
#else
last_sent_len = 0;
#endif
mav_pkt_len = 0;

high_offset = (feature_mavlink_framing == MAVLINK_FRAMING_HIGHPRI) ? extract_hipri(max_xmit) : -1;

slen = serial_read_available();

// see if we have more complete MAVLink frames in the serial
// buffer that we can fit in this packet
while (slen >= 8) {
register uint8_t c = serial_peek();
if (c != MAVLINK10_STX) {
register uint8_t c = serial_peekx(0);
register uint8_t extra_len = 8;
if (c != MAVLINK10_STX && c != MAVLINK20_STX) {
// its not a MAVLink packet
return last_sent_len;
}
c = serial_peek2();
if (c >= 255 - 8 ||
c+8 > max_xmit - last_sent_len) {
if (c == MAVLINK20_STX) {
extra_len += 4;
if (serial_peekx(2) & 1) {
// signed packet
extra_len += 13;
}
}
// fetch the length byte
c = serial_peekx(1);
if (c >= 255 - extra_len ||
c+extra_len > max_xmit - last_sent_len) {
// it won't fit
break;
}
if (c+8 > slen) {
if (c+extra_len > slen) {
// we don't have the full MAVLink packet in
// the serial buffer
break;
}

// If we are using the special highpri mode, we might skip some override packets
if(high_offset != -1 && high_offset != offset && serial_peekx(5) == MSG_TYP_RC_OVERRIDE && c == MSG_LEN_RC_OVERRIDE) {
// printf("skipping rc\r\n");
c += 8;
}
else {
c += 8;

// we can add another MAVLink frame to the packet
serial_read_buf(&last_sent[last_sent_len], c);
memcpy(&buf[last_sent_len], &last_sent[last_sent_len], c);

check_heartbeat(buf+last_sent_len);
}
c += extra_len;

// we can add another MAVLink frame to the packet
serial_read_buf(&last_sent[last_sent_len], c);
memcpy(&buf[last_sent_len], &last_sent[last_sent_len], c);

check_heartbeat(buf+last_sent_len);

last_sent_len += c;
slen -= c;
offset += c;
}

return last_sent_len;
Expand Down Expand Up @@ -270,11 +217,7 @@ packet_get_next(register uint8_t max_xmit, __xdata uint8_t *buf)
last_sent_is_injected = false;

slen = serial_read_available();
if (force_resend ||
(feature_opportunistic_resend &&
last_sent_is_resend == false &&
last_sent_len != 0 &&
slen < PACKET_RESEND_THRESHOLD)) {
if (force_resend) {
if (max_xmit < last_sent_len) {
return 0;
}
Expand Down Expand Up @@ -348,8 +291,8 @@ packet_get_next(register uint8_t max_xmit, __xdata uint8_t *buf)

// We are now looking for a new packet (mav_pkt_len == 0)
while (slen > 0) {
register uint8_t c = serial_peek();
if (c == MAVLINK10_STX) {
register uint8_t c = serial_peekx(0);
if (c == MAVLINK10_STX || c == MAVLINK20_STX) {
if (slen == 1) {
// we got a bare MAVLink header byte
if (last_sent_len == 0) {
Expand All @@ -362,9 +305,9 @@ packet_get_next(register uint8_t max_xmit, __xdata uint8_t *buf)
}
break;
}
mav_pkt_len = serial_peek2();
if (mav_pkt_len >= 255-8 ||
mav_pkt_len+8 > mav_max_xmit) {
mav_pkt_len = serial_peekx(1);
if (mav_pkt_len >= 255-(8+4+13) ||
mav_pkt_len+(8+4+13) > mav_max_xmit) {
// its too big for us to cope with
mav_pkt_len = 0;
last_sent[last_sent_len++] = serial_read(); // Send the STX and try again (we will lose framing)
Expand All @@ -375,6 +318,13 @@ packet_get_next(register uint8_t max_xmit, __xdata uint8_t *buf)
// the length byte doesn't include
// the header or CRC
mav_pkt_len += 8;
if (c == MAVLINK20_STX) {
mav_pkt_len += 4;
if (slen > 2 && (serial_peekx(2) & 1)) {
// it is signed
mav_pkt_len += 13;
}
}

if (last_sent_len != 0) {
// send what we've got so far,
Expand Down
3 changes: 2 additions & 1 deletion Firmware/radio/packet.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ extern void packet_set_serial_speed(uint16_t speed);
///
extern void packet_inject(__xdata uint8_t *buf, __pdata uint8_t len);

// mavlink 1.0 marker
// mavlink 1.0 and 2.0 markers
#define MAVLINK10_STX 254
#define MAVLINK20_STX 253

6 changes: 2 additions & 4 deletions Firmware/radio/parameters.c
Original file line number Diff line number Diff line change
Expand Up @@ -69,9 +69,9 @@ __code const struct parameter_info {
{"LBT_RSSI", 0},
{"MANCHESTER", 0},
{"RTSCTS", 0},
{"MAX_WINDOW", 131},
{"MAX_WINDOW", 131},
#ifdef INCLUDE_AES
{"ENCRYPTION_LEVEL", 0}, // no Enycryption (0), 128 or 256 bit key
{"ENCRYPTION_LEVEL", 0}, // no Enycryption (0), 128 or 256 bit key
#endif
};

Expand Down Expand Up @@ -210,8 +210,6 @@ param_set(__data enum ParamID param, __pdata param_t value)
break;

case PARAM_OPPRESEND:
feature_opportunistic_resend = value?true:false;
value = feature_opportunistic_resend?1:0;
break;

case PARAM_RTSCTS:
Expand Down
2 changes: 1 addition & 1 deletion Firmware/radio/parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ enum ParamID {
PARAM_TXPOWER, // transmit power (dBm)
PARAM_ECC, // ECC using golay encoding
PARAM_MAVLINK, // MAVLink framing, 0=ignore, 1=use, 2=rc-override
PARAM_OPPRESEND, // opportunistic resend
PARAM_OPPRESEND, // opportunistic resend // DISABLED
PARAM_MIN_FREQ, // min frequency in MHz
PARAM_MAX_FREQ, // max frequency in MHz
PARAM_NUM_CHANNELS, // number of hopping channels
Expand Down
4 changes: 2 additions & 2 deletions Firmware/radio/product.mk
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
# Makefile for the Si1000 radio application
#

VERSION_MAJOR = 1
VERSION_MINOR = 13
VERSION_MAJOR = 2
VERSION_MINOR = 0

PRODUCT = radio~$(BOARD)
PRODUCT_DIR := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST))))
Expand Down
46 changes: 46 additions & 0 deletions Firmware/radio/segment.rules
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
# segment.rules files assign source code modules to specific banks
# These files are only used when we build code with cpu supporting banking
# The final segment.rules file is constructed from any segment.rules found in
# the search path, defined in the CPU Makefile
# When building bankable code, the bank-alloc.py script automatically allocates
# modules to banks. segment.rules files provide hints, instructing the script
# as to which files are safe to move around and which files to leave alone
# In other words, only specify a rule for a file if you need to
# comments starting with "#" are supported
# The file spec in rules is actually interpreted as a python regex so you can
# write a rule that will match multiple files
#
# general rules --
# SDCC's standard libraries will always go in CSEG - We don't touch them
# Interrupt code must be in HOME. Specify all files with an ISR here
# All files without an associated rule get allocated to a bank automatically

# Files with ISRs must be in HOME
BANK3 timer.c
BANK3 radio.c
BANK3 serial.c
HOME main.c
BANK3 printfl.c

BANK3 rtc.c
BANK3 pins_user.c
BANK3 mavlink.c

BANK3 packet.c
BANK3 golay.c
BANK3 crc.c

# There is a Parameter shared between these functions and should be in the same bank?
BANK3 parameters.c
BANK3 aesEncrypt.c
BANK3 at.c
BANK3 main_init.c

# freq_hooping needs to be in the same bank as tdm (due to __nonbanked to save space)
BANK3 freq_hopping.c
BANK3 tdm.c


# Flash MUST be in bank3 as it needs to read the end of this page
BANK3 flash.c

Loading