Merge branch 'contiki'

This commit is contained in:
Harald Pichler 2017-09-05 11:14:11 +02:00
commit 3f6cb4e795
177 changed files with 5479 additions and 4613 deletions

View file

@ -14,7 +14,7 @@ before_script:
## Install doxygen
- if [ ${BUILD_CATEGORY:-0} = doxygen ] ; then
sudo add-apt-repository ppa:libreoffice/libreoffice-4-4 -y && sudo apt-get -qq update &&
sudo add-apt-repository ppa:libreoffice/ppa -y && sudo apt-get -qq update &&
sudo apt-get --no-install-suggests --no-install-recommends -qq install doxygen &&
doxygen --version ;
fi
@ -85,7 +85,7 @@ before_script:
- if [ ${BUILD_ARCH:-0} = jn516x ] ; then
$WGET http://simonduq.github.io/resources/ba-elf-gcc-4.7.4-part1.tar.bz2 &&
$WGET http://simonduq.github.io/resources/ba-elf-gcc-4.7.4-part2.tar.bz2 &&
$WGET http://simonduq.github.io/resources/jn516x-sdk-4163.tar.bz2 &&
$WGET http://simonduq.github.io/resources/jn516x-sdk-4163-1416.tar.bz2 &&
mkdir /tmp/jn516x-sdk /tmp/ba-elf-gcc &&
tar xjf jn516x-sdk-*.tar.bz2 -C /tmp/jn516x-sdk &&
tar xjf ba-elf-gcc-*part1.tar.bz2 -C /tmp/ba-elf-gcc &&
@ -163,3 +163,4 @@ env:
- BUILD_TYPE='llsec' MAKE_TARGETS='cooja'
- BUILD_TYPE='compile-avr' BUILD_CATEGORY='compile' BUILD_ARCH='avr-rss2'
- BUILD_TYPE='ieee802154'
- BUILD_TYPE='tsch'

View file

@ -107,7 +107,7 @@ int coap_obs_remove_observee_by_token(uip_ipaddr_t *addr, uint16_t port,
int coap_obs_remove_observee_by_url(uip_ipaddr_t *addr, uint16_t port,
const char *url);
void coap_handle_notification(uip_ipaddr_t *, uint16_t port,
void coap_handle_notification(uip_ipaddr_t *addr, uint16_t port,
coap_packet_t *notification);
coap_observee_t *coap_obs_request_registration(uip_ipaddr_t *addr,

View file

@ -249,6 +249,8 @@ coap_notify_observers_sub(resource_t *resource, const char *subpath)
if(notification->code < BAD_REQUEST_4_00) {
coap_set_header_observe(notification, (obs->obs_counter)++);
/* mask out to keep the CoAP observe option length <= 3 bytes */
obs->obs_counter &= 0xffffff;
}
coap_set_token(notification, obs->token, obs->token_len);
@ -276,6 +278,8 @@ coap_observe_handler(resource_t *resource, void *request, void *response)
coap_req->uri_path, coap_req->uri_path_len);
if(obs) {
coap_set_header_observe(coap_res, (obs->obs_counter)++);
/* mask out to keep the CoAP observe option length <= 3 bytes */
obs->obs_counter &= 0xffffff;
/*
* Following payload is for demonstration purposes only.
* A subscription should return the same representation as a normal GET.

View file

@ -529,8 +529,21 @@ coap_parse_message(void *packet, uint8_t *data, uint16_t data_len)
++current_option;
}
if(current_option + option_length > data + data_len) {
/* Malformed CoAP - out of bounds */
PRINTF("BAD REQUEST: options outside data packet: %u > %u\n",
(unsigned)(current_option + option_length - data), data_len);
return BAD_REQUEST_4_00;
}
option_number += option_delta;
if(option_number > COAP_OPTION_SIZE1) {
/* Malformed CoAP - out of bounds */
PRINTF("BAD REQUEST: option number too large: %u\n", option_number);
return BAD_REQUEST_4_00;
}
PRINTF("OPTION %u (delta %u, len %zu): ", option_number, option_delta,
option_length);

View file

@ -130,6 +130,7 @@ typedef enum {
/*---------------------------------------------------------------------------*/
/* Protothread send macros */
#define PT_MQTT_WRITE_BYTES(conn, data, len) \
conn->out_write_pos = 0; \
while(write_bytes(conn, data, len)) { \
PT_WAIT_UNTIL(pt, (conn)->out_buffer_sent); \
}
@ -147,15 +148,19 @@ typedef enum {
*/
#define PT_MQTT_WAIT_SEND() \
do { \
process_post(PROCESS_CURRENT(), mqtt_continue_send_event, NULL); \
if (PROCESS_ERR_OK == \
process_post(PROCESS_CURRENT(), mqtt_continue_send_event, NULL)) { \
do { \
PROCESS_WAIT_EVENT(); \
if(ev == mqtt_abort_now_event) { \
conn->state = MQTT_CONN_STATE_ABORT_IMMEDIATE; \
PT_EXIT(&conn->out_proto_thread); \
PT_INIT(&conn->out_proto_thread); \
process_post(PROCESS_CURRENT(), ev, data); \
} else if(ev >= mqtt_event_min && ev <= mqtt_event_max) { \
process_post(PROCESS_CURRENT(), ev, data); \
} \
} while (ev != mqtt_continue_send_event); \
} \
} while(0)
/*---------------------------------------------------------------------------*/
static process_event_t mqtt_do_connect_tcp_event;
@ -751,6 +756,8 @@ handle_connack(struct mqtt_connection *conn)
call_event(conn,
MQTT_EVENT_CONNECTION_REFUSED_ERROR,
&conn->in_packet.payload[1]);
abort_connection(conn);
return;
}
conn->out_packet.qos_state = MQTT_QOS_STATE_GOT_ACK;
@ -1186,8 +1193,8 @@ PROCESS_THREAD(mqtt_process, ev, data)
if(conn->state == MQTT_CONN_STATE_SENDING_MQTT_DISCONNECT) {
if(conn->out_buffer_sent == 1) {
PT_INIT(&conn->out_proto_thread);
while(disconnect_pt(&conn->out_proto_thread, conn) < PT_EXITED &&
conn->state != MQTT_CONN_STATE_ABORT_IMMEDIATE) {
while(conn->state != MQTT_CONN_STATE_ABORT_IMMEDIATE &&
disconnect_pt(&conn->out_proto_thread, conn) < PT_EXITED) {
PT_MQTT_WAIT_SEND();
}
abort_connection(conn);
@ -1204,8 +1211,8 @@ PROCESS_THREAD(mqtt_process, ev, data)
if(conn->out_buffer_sent == 1 &&
conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER) {
PT_INIT(&conn->out_proto_thread);
while(pingreq_pt(&conn->out_proto_thread, conn) < PT_EXITED &&
conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER) {
while(conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER &&
pingreq_pt(&conn->out_proto_thread, conn) < PT_EXITED) {
PT_MQTT_WAIT_SEND();
}
}
@ -1217,8 +1224,8 @@ PROCESS_THREAD(mqtt_process, ev, data)
if(conn->out_buffer_sent == 1 &&
conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER) {
PT_INIT(&conn->out_proto_thread);
while(subscribe_pt(&conn->out_proto_thread, conn) < PT_EXITED &&
conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER) {
while(conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER &&
subscribe_pt(&conn->out_proto_thread, conn) < PT_EXITED) {
PT_MQTT_WAIT_SEND();
}
}
@ -1230,8 +1237,8 @@ PROCESS_THREAD(mqtt_process, ev, data)
if(conn->out_buffer_sent == 1 &&
conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER) {
PT_INIT(&conn->out_proto_thread);
while(unsubscribe_pt(&conn->out_proto_thread, conn) < PT_EXITED &&
conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER) {
while(conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER &&
unsubscribe_pt(&conn->out_proto_thread, conn) < PT_EXITED) {
PT_MQTT_WAIT_SEND();
}
}
@ -1243,8 +1250,8 @@ PROCESS_THREAD(mqtt_process, ev, data)
if(conn->out_buffer_sent == 1 &&
conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER) {
PT_INIT(&conn->out_proto_thread);
while(publish_pt(&conn->out_proto_thread, conn) < PT_EXITED &&
conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER) {
while(conn->state == MQTT_CONN_STATE_CONNECTED_TO_BROKER &&
publish_pt(&conn->out_proto_thread, conn) < PT_EXITED) {
PT_MQTT_WAIT_SEND();
}
}
@ -1331,7 +1338,9 @@ mqtt_connect(struct mqtt_connection *conn, char *host, uint16_t port,
conn->connect_vhdr_flags |= MQTT_VHDR_CLEAN_SESSION_FLAG;
/* convert the string IPv6 address to a numeric IPv6 address */
uiplib_ip6addrconv(host, &ip6addr);
if(uiplib_ip6addrconv(host, &ip6addr) == 0) {
return MQTT_STATUS_ERROR;
}
uip_ipaddr_copy(&(conn->server_ip), ipaddr);

View file

@ -196,7 +196,7 @@ typedef enum {
MQTT_CONN_STATE_ERROR,
MQTT_CONN_STATE_DNS_ERROR,
MQTT_CONN_STATE_DISCONNECTING,
MQTT_CONN_STATE_ABORT_IMMEDIATE,
MQTT_CONN_STATE_NOT_CONNECTED,
MQTT_CONN_STATE_DNS_LOOKUP,
MQTT_CONN_STATE_TCP_CONNECTING,
@ -204,7 +204,6 @@ typedef enum {
MQTT_CONN_STATE_CONNECTING_TO_BROKER,
MQTT_CONN_STATE_CONNECTED_TO_BROKER,
MQTT_CONN_STATE_SENDING_MQTT_DISCONNECT,
MQTT_CONN_STATE_ABORT_IMMEDIATE,
} mqtt_conn_state_t;
/*---------------------------------------------------------------------------*/
struct mqtt_string {

View file

@ -254,6 +254,7 @@ make_addresses(void *p)
{
uint8_t i, j = 0;
uint16_t numprinted;
numprinted = httpd_snprintf((char *)uip_appdata, uip_mss(),httpd_cgi_addrh);
for (i=0; i<UIP_DS6_ADDR_NB;i++) {
if (uip_ds6_if.addr_list[i].isused) {
@ -280,7 +281,7 @@ PT_THREAD(addresses(struct httpd_state *s, char *ptr))
static unsigned short
make_neighbors(void *p)
{
uint8_t i,j=0;
uint8_t j=0;
uint16_t numprinted;
numprinted = httpd_snprintf((char *)uip_appdata, uip_mss(),httpd_cgi_addrh);
uip_ds6_nbr_t *nbr;
@ -312,7 +313,7 @@ make_routes(void *p)
static const char httpd_cgi_rtes1[] HTTPD_STRING_ATTR = "(%u (via ";
static const char httpd_cgi_rtes2[] HTTPD_STRING_ATTR = ") %lus<br>";
static const char httpd_cgi_rtes3[] HTTPD_STRING_ATTR = ")<br>";
uint8_t i,j=0;
uint8_t j=0;
uint16_t numprinted;
uip_ds6_route_t *r;
@ -323,7 +324,7 @@ make_routes(void *p)
j++;
numprinted += httpd_cgi_sprint_ip6(r->ipaddr, uip_appdata + numprinted);
numprinted += httpd_snprintf((char *)uip_appdata+numprinted, uip_mss()-numprinted, httpd_cgi_rtes1, r->length);
numprinted += httpd_cgi_sprint_ip6(uip_ds6_route_nexthop(r), uip_appdata + numprinted);
numprinted += httpd_cgi_sprint_ip6(*(uip_ds6_route_nexthop(r)), uip_appdata + numprinted);
if(r->state.lifetime < 3600) {
numprinted += httpd_snprintf((char *)uip_appdata+numprinted, uip_mss()-numprinted, httpd_cgi_rtes2, r->state.lifetime);
} else {

View file

@ -148,13 +148,6 @@
#endif /* NBR_TABLE_FIND_REMOVABLE */
#endif /* UIP_CONF_IPV6_RPL */
/* RPL_CONF_MOP specifies the RPL mode of operation that will be
* advertised by the RPL root. Possible values: RPL_MOP_NO_DOWNWARD_ROUTES,
* RPL_MOP_NON_STORING, RPL_MOP_STORING_NO_MULTICAST, RPL_MOP_STORING_MULTICAST */
#ifndef RPL_CONF_MOP
#define RPL_CONF_MOP RPL_MOP_STORING_NO_MULTICAST
#endif /* RPL_CONF_MOP */
/* UIP_CONF_MAX_ROUTES specifies the maximum number of routes that each
node will be able to handle. */
#ifndef UIP_CONF_MAX_ROUTES

View file

@ -107,9 +107,6 @@ slip_send(void)
ptr = &uip_buf[UIP_LLH_LEN];
for(i = 0; i < uip_len; ++i) {
if(i == UIP_TCPIP_HLEN) {
ptr = (uint8_t *)uip_appdata;
}
c = *ptr++;
if(c == SLIP_END) {
slip_arch_writeb(SLIP_ESC);
@ -161,6 +158,7 @@ rxbuf_init(void)
static uint16_t
slip_poll_handler(uint8_t *outbuf, uint16_t blen)
{
#ifdef SLIP_CONF_MICROSOFT_CHAT
/* This is a hack and won't work across buffer edge! */
if(rxbuf[begin] == 'C') {
int i;
@ -177,6 +175,8 @@ slip_poll_handler(uint8_t *outbuf, uint16_t blen)
return 0;
}
}
#endif /* SLIP_CONF_MICROSOFT_CHAT */
#ifdef SLIP_CONF_ANSWER_MAC_REQUEST
else if(rxbuf[begin] == '?') {
/* Used by tapslip6 to request mac for auto configure */
@ -425,11 +425,13 @@ slip_input_byte(unsigned char c)
}
rxbuf[cur_end] = c;
#ifdef SLIP_CONF_MICROSOFT_CHAT
/* There could be a separate poll routine for this. */
if(c == 'T' && rxbuf[begin] == 'C') {
process_poll(&slip_process);
return 1;
}
#endif /* SLIP_CONF_MICROSOFT_CHAT */
if(c == SLIP_END) {
/*

View file

@ -83,7 +83,7 @@ ringbufindex_peek_put(const struct ringbufindex *r)
if(((r->put_ptr - r->get_ptr) & r->mask) == r->mask) {
return -1;
}
return (r->put_ptr + 1) & r->mask;
return r->put_ptr;
}
/* Remove the first element and return its index */
int
@ -118,7 +118,7 @@ ringbufindex_peek_get(const struct ringbufindex *r)
first one. If there are no bytes left, we return -1.
*/
if(((r->put_ptr - r->get_ptr) & r->mask) > 0) {
return (r->get_ptr + 1) & r->mask;
return r->get_ptr;
} else {
return -1;
}

View file

@ -48,25 +48,72 @@ struct ringbufindex {
uint8_t put_ptr, get_ptr;
};
/* Initialize a ring buffer. The size must be a power of two */
/**
* \brief Initialize a ring buffer. The size must be a power of two
* \param r Pointer to ringbufindex
* \param size Size of ring buffer
*/
void ringbufindex_init(struct ringbufindex *r, uint8_t size);
/* Put one element to the ring buffer */
/**
* \brief Put one element to the ring buffer
* \param r Pointer to ringbufindex
* \retval 0 Failure; the ring buffer is full
* \retval 1 Success; an element is added
*/
int ringbufindex_put(struct ringbufindex *r);
/* Check if there is space to put an element.
* Return the index where the next element is to be added */
/**
* \brief Check if there is space to put an element.
* \param r Pinter to ringbufindex
* \retval >= 0 The index where the next element is to be added.
* \retval -1 Failure; the ring buffer is full
*/
int ringbufindex_peek_put(const struct ringbufindex *r);
/* Remove the first element and return its index */
/**
* \brief Remove the first element and return its index
* \param r Pinter to ringbufindex
* \retval >= 0 The index of the first element
* \retval -1 No element in the ring buffer
*/
int ringbufindex_get(struct ringbufindex *r);
/* Return the index of the first element
* (which will be removed if calling ringbufindex_peek) */
/**
* \brief Return the index of the first element which will be removed if calling
* ringbufindex_get.
* \param r Pinter to ringbufindex
* \retval >= 0 The index of the first element
* \retval -1 No element in the ring buffer
*/
int ringbufindex_peek_get(const struct ringbufindex *r);
/* Return the ring buffer size */
/**
* \brief Return the ring buffer size
* \param r Pinter to ringbufindex
* \return The size of the ring buffer
*/
int ringbufindex_size(const struct ringbufindex *r);
/* Return the number of elements currently in the ring buffer */
/**
* \brief Return the number of elements currently in the ring buffer.
* \param r Pinter to ringbufindex
* \return The number of elements in the ring buffer
*/
int ringbufindex_elements(const struct ringbufindex *r);
/* Is the ring buffer full? */
/**
* \brief Is the ring buffer full?
* \retval 0 Not full
* \retval 1 Full
*/
int ringbufindex_full(const struct ringbufindex *r);
/* Is the ring buffer empty? */
/**
* \brief Is the ring buffer empty?
* \retval 0 Not empty
* \retval 1 Empty
*/
int ringbufindex_empty(const struct ringbufindex *r);
#endif /* __RINGBUFINDEX_H__ */

View file

@ -35,6 +35,10 @@
#include <string.h>
#define printf(...)
static uip_ip6addr_t ip64_prefix = {{ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0xff, 0xff, 0, 0, 0, 0}};
static uint8_t ip64_prefix_len = 96;
/*---------------------------------------------------------------------------*/
void
ip64_addr_copy4(uip_ip4addr_t *dest, const uip_ip4addr_t *src)
@ -56,20 +60,7 @@ ip64_addr_4to6(const uip_ip4addr_t *ipv4addr,
addresses. It returns 0 if it failed to convert the address and
non-zero if it could successfully convert the address. */
/* The IPv4 address is encoded as an IPv6-encoded IPv4 address in
the ::ffff:0000/24 prefix.*/
ipv6addr->u8[0] = 0;
ipv6addr->u8[1] = 0;
ipv6addr->u8[2] = 0;
ipv6addr->u8[3] = 0;
ipv6addr->u8[4] = 0;
ipv6addr->u8[5] = 0;
ipv6addr->u8[6] = 0;
ipv6addr->u8[7] = 0;
ipv6addr->u8[8] = 0;
ipv6addr->u8[9] = 0;
ipv6addr->u8[10] = 0xff;
ipv6addr->u8[11] = 0xff;
uip_ipaddr_copy(ipv6addr, &ip64_prefix);
ipv6addr->u8[12] = ipv4addr->u8[0];
ipv6addr->u8[13] = ipv4addr->u8[1];
ipv6addr->u8[14] = ipv4addr->u8[2];
@ -90,21 +81,7 @@ ip64_addr_6to4(const uip_ip6addr_t *ipv6addr,
returns 0 if it failed to convert the address and non-zero if it
could successfully convert the address. */
/* If the IPv6 address is an IPv6-encoded
IPv4 address (i.e. in the ::ffff:0/8 prefix), we simply use the
IPv4 addresses directly. */
if(ipv6addr->u8[0] == 0 &&
ipv6addr->u8[1] == 0 &&
ipv6addr->u8[2] == 0 &&
ipv6addr->u8[3] == 0 &&
ipv6addr->u8[4] == 0 &&
ipv6addr->u8[5] == 0 &&
ipv6addr->u8[6] == 0 &&
ipv6addr->u8[7] == 0 &&
ipv6addr->u8[8] == 0 &&
ipv6addr->u8[9] == 0 &&
ipv6addr->u8[10] == 0xff &&
ipv6addr->u8[11] == 0xff) {
if(ip64_addr_is_ip64(ipv6addr)) {
ipv4addr->u8[0] = ipv6addr->u8[12];
ipv4addr->u8[1] = ipv6addr->u8[13];
ipv4addr->u8[2] = ipv6addr->u8[14];
@ -121,3 +98,16 @@ ip64_addr_6to4(const uip_ip6addr_t *ipv6addr,
return 0;
}
/*---------------------------------------------------------------------------*/
int
ip64_addr_is_ip64(const uip_ip6addr_t *ipv6addr)
{
return uip_ipaddr_prefixcmp(ipv6addr, &ip64_prefix, ip64_prefix_len);
}
/*---------------------------------------------------------------------------*/
void
ip64_addr_set_prefix(const uip_ip6addr_t *prefix, uint8_t prefix_len)
{
uip_ipaddr_copy(&ip64_prefix, prefix);
ip64_prefix_len = prefix_len;
}
/*---------------------------------------------------------------------------*/

View file

@ -58,6 +58,9 @@ int ip64_addr_6to4(const uip_ip6addr_t *ipv6addr,
int ip64_addr_4to6(const uip_ip4addr_t *ipv4addr,
uip_ip6addr_t *ipv6addr);
int ip64_addr_is_ip64(const uip_ip6addr_t *ipv6addr);
void ip64_addr_set_prefix(const uip_ip6addr_t *prefix, uint8_t prefix_len);
#endif /* IP64_ADDR_H */

View file

@ -1094,7 +1094,7 @@ resolv_set_hostname(const char *hostname)
/* Add the .local suffix if it isn't already there */
if(strlen(resolv_hostname) < 7 ||
strcasecmp(resolv_hostname + strlen(resolv_hostname) - 6, ".local") != 0) {
strncat(resolv_hostname, ".local", RESOLV_CONF_MAX_DOMAIN_NAME_SIZE);
strncat(resolv_hostname, ".local", RESOLV_CONF_MAX_DOMAIN_NAME_SIZE - strlen(resolv_hostname));
}
PRINTF("resolver: hostname changed to \"%s\"\n", resolv_hostname);
@ -1248,8 +1248,8 @@ remove_trailing_dots(const char *name) {
static char dns_name_without_dots[RESOLV_CONF_MAX_DOMAIN_NAME_SIZE + 1];
size_t len = strlen(name);
if(name[len - 1] == '.') {
strncpy(dns_name_without_dots, name, sizeof(dns_name_without_dots));
if(len && name[len - 1] == '.') {
strncpy(dns_name_without_dots, name, RESOLV_CONF_MAX_DOMAIN_NAME_SIZE);
while(len && (dns_name_without_dots[len - 1] == '.')) {
dns_name_without_dots[--len] = 0;
}
@ -1309,7 +1309,7 @@ resolv_query(const char *name)
memset(nameptr, 0, sizeof(*nameptr));
strncpy(nameptr->name, name, sizeof(nameptr->name));
strncpy(nameptr->name, name, sizeof(nameptr->name) - 1);
nameptr->state = STATE_NEW;
nameptr->seqno = seqno;
++seqno;
@ -1479,7 +1479,7 @@ resolv_found(char *name, uip_ipaddr_t * ipaddr)
}
/* Re-add the .local suffix */
strncat(resolv_hostname, ".local", RESOLV_CONF_MAX_DOMAIN_NAME_SIZE);
strncat(resolv_hostname, ".local", RESOLV_CONF_MAX_DOMAIN_NAME_SIZE - strlen(resolv_hostname));
start_name_collision_check(CLOCK_SECOND * 5);
} else if(mdns_state == MDNS_STATE_READY) {

View file

@ -102,9 +102,6 @@ slipdev_send(void)
ptr = &uip_buf[UIP_LLH_LEN];
for(i = 0; i < uip_len; ++i) {
if(i == UIP_TCPIP_HLEN) {
ptr = (uint8_t *)uip_appdata;
}
c = *ptr++;
switch(c) {
case SLIP_END:

View file

@ -490,26 +490,8 @@ void uip_reass_over(void);
*
* The uip_aligned_buf array is used to hold incoming and outgoing
* packets. The device driver should place incoming data into this
* buffer. When sending data, the device driver should read the link
* level headers and the TCP/IP headers from this buffer. The size of
* the link level headers is configured by the UIP_LLH_LEN define.
*
* \note The application data need not be placed in this buffer, so
* the device driver must read it from the place pointed to by the
* uip_appdata pointer as illustrated by the following example:
\code
void
devicedriver_send(void)
{
hwsend(&uip_buf[0], UIP_LLH_LEN);
if(uip_len <= UIP_LLH_LEN + UIP_TCPIP_HLEN) {
hwsend(&uip_buf[UIP_LLH_LEN], uip_len - UIP_LLH_LEN);
} else {
hwsend(&uip_buf[UIP_LLH_LEN], UIP_TCPIP_HLEN);
hwsend(uip_appdata, uip_len - UIP_TCPIP_HLEN - UIP_LLH_LEN);
}
}
\endcode
* buffer. When sending data, the device driver should read the
* outgoing data from this buffer.
*/
typedef union {

View file

@ -120,10 +120,6 @@ uint16_t uip_ipchksum(void);
* The TCP checksum is the Internet checksum of data contents of the
* TCP segment, and a pseudo-header as defined in RFC793.
*
* \note The uip_appdata pointer that points to the packet data may
* point anywhere in memory, so it is not possible to simply calculate
* the Internet checksum of the contents of the uip_buf buffer.
*
* \return The TCP checksum of the TCP segment in uip_buf and pointed
* to by uip_appdata.
*/

View file

@ -163,7 +163,6 @@ create_msg(CC_REGISTER_ARG struct dhcp_msg *m)
memset(&m->chaddr[s.mac_len], 0, sizeof(m->chaddr) - s.mac_len);
memset(m->sname, 0, sizeof(m->sname));
strcpy((char *)m->sname, "Thingsquare");
memset(m->file, 0, sizeof(m->file));

View file

@ -39,6 +39,9 @@
#include <stdio.h>
#define DEBUG DEBUG_NONE
#include "net/ip/uip-debug.h"
PROCESS(ip64_ipv4_dhcp_process, "IPv4 DHCP");
uip_ipaddr_t uip_hostaddr; /* Needed because it is referenced by dhcpc.c */
@ -48,7 +51,7 @@ uip_ipaddr_t uip_hostaddr; /* Needed because it is referenced by dhcpc.c */
void
ip64_ipv4_dhcp_init(void)
{
printf("Starting DHCPv4\n");
printf("IP64: Starting DHCPv4\n");
process_start(&ip64_ipv4_dhcp_process, NULL);
}
/*---------------------------------------------------------------------------*/
@ -58,10 +61,10 @@ PROCESS_THREAD(ip64_ipv4_dhcp_process, ev, data)
ip64_dhcpc_init(&ip64_eth_addr, sizeof(ip64_eth_addr));
printf("Inited\n");
PRINTF("IP64: Inited\n");
ip64_dhcpc_request();
printf("Requested\n");
PRINTF("IP64: Requested\n");
while(1) {
PROCESS_WAIT_EVENT();
@ -78,15 +81,22 @@ void
ip64_dhcpc_configured(const struct ip64_dhcpc_state *s)
{
uip_ip6addr_t ip6dnsaddr;
printf("DHCP Configured with %d.%d.%d.%d\n",
PRINTF("IP64: DHCP Configured with %d.%d.%d.%d\n",
s->ipaddr.u8[0], s->ipaddr.u8[1],
s->ipaddr.u8[2], s->ipaddr.u8[3]);
ip64_set_hostaddr((uip_ip4addr_t *)&s->ipaddr);
ip64_set_netmask((uip_ip4addr_t *)&s->netmask);
ip64_set_draddr((uip_ip4addr_t *)&s->default_router);
if(!uip_ip4addr_cmp((uip_ip4addr_t *)&s->dnsaddr, &uip_all_zeroes_addr)) {
/* Note: Currently we assume only one DNS server */
uip_ipaddr_t * dns = uip_nameserver_get(0);
/* Only update DNS entry if it is empty or already IPv4 */
if(uip_is_addr_unspecified(dns) || ip64_addr_is_ip64(dns)) {
ip64_addr_4to6((uip_ip4addr_t *)&s->dnsaddr, &ip6dnsaddr);
// mdns_conf(&ip6dnsaddr);
uip_nameserver_update(&ip6dnsaddr, uip_ntohs(s->lease_time[0])*65536ul + uip_ntohs(s->lease_time[1]));
}
}
}
/*---------------------------------------------------------------------------*/
void

View file

@ -162,7 +162,7 @@ struct uip_mcast6_driver {
#define UIP_MCAST6 smrf_driver
#elif UIP_MCAST6_ENGINE == UIP_MCAST6_ENGINE_ESMRF
#define RPL_CONF_MULTICAST 1
#define RPL_WITH_MULTICAST 1
#define UIP_MCAST6 esmrf_driver
#else

View file

@ -547,8 +547,8 @@ websocket_open(struct websocket *s, const char *url,
websocket_callback c)
{
int ret;
char host[MAX_HOSTLEN];
char path[MAX_PATHLEN];
char host[MAX_HOSTLEN + 1] = {0};
char path[MAX_PATHLEN + 1] = {0};
uint16_t port;
uip_ipaddr_t addr;

View file

@ -183,7 +183,7 @@ frame802154_has_panid(frame802154_fcf_t *fcf, int *has_src_pan_id, int *has_dest
} else {
/* No PAN ID in ACK */
if(fcf->frame_type != FRAME802154_ACKFRAME) {
if(!fcf->panid_compression && fcf->src_addr_mode & 3) {
if(!fcf->panid_compression && (fcf->src_addr_mode & 3)) {
/* If compressed, don't include source PAN ID */
src_pan_id = 1;
}
@ -205,7 +205,7 @@ frame802154_has_panid(frame802154_fcf_t *fcf, int *has_src_pan_id, int *has_dest
int
frame802154_check_dest_panid(frame802154_t *frame)
{
int has_dest_panid;
int has_dest_panid = 0;
if(frame == NULL) {
return 0;
@ -304,7 +304,7 @@ field_len(frame802154_t *p, field_length_t *flen)
* up to the caller. */
if(p->fcf.frame_version < FRAME802154_IEEE802154E_2012) {
/* Set PAN ID compression bit if src pan id matches dest pan id. */
if(p->fcf.dest_addr_mode & 3 && p->fcf.src_addr_mode & 3 &&
if((p->fcf.dest_addr_mode & 3) && (p->fcf.src_addr_mode & 3) &&
p->src_pid == p->dest_pid) {
p->fcf.panid_compression = 1;
} else {
@ -362,6 +362,20 @@ frame802154_hdrlen(frame802154_t *p)
return 2 + flen.seqno_len + flen.dest_pid_len + flen.dest_addr_len +
flen.src_pid_len + flen.src_addr_len + flen.aux_sec_len;
}
void
frame802154_create_fcf(frame802154_fcf_t *fcf, uint8_t *buf)
{
buf[0] = (fcf->frame_type & 7) |
((fcf->security_enabled & 1) << 3) |
((fcf->frame_pending & 1) << 4) |
((fcf->ack_required & 1) << 5) |
((fcf->panid_compression & 1) << 6);
buf[1] = ((fcf->sequence_number_suppression & 1)) |
((fcf->ie_list_present & 1)) << 1 |
((fcf->dest_addr_mode & 3) << 2) |
((fcf->frame_version & 3) << 4) |
((fcf->src_addr_mode & 3) << 6);
}
/*----------------------------------------------------------------------------*/
/**
* \brief Creates a frame for transmission over the air. This function is
@ -388,17 +402,7 @@ frame802154_create(frame802154_t *p, uint8_t *buf)
/* OK, now we have field lengths. Time to actually construct */
/* the outgoing frame, and store it in buf */
buf[0] = (p->fcf.frame_type & 7) |
((p->fcf.security_enabled & 1) << 3) |
((p->fcf.frame_pending & 1) << 4) |
((p->fcf.ack_required & 1) << 5) |
((p->fcf.panid_compression & 1) << 6);
buf[1] = ((p->fcf.sequence_number_suppression & 1)) |
((p->fcf.ie_list_present & 1)) << 1 |
((p->fcf.dest_addr_mode & 3) << 2) |
((p->fcf.frame_version & 3) << 4) |
((p->fcf.src_addr_mode & 3) << 6);
frame802154_create_fcf(&p->fcf, buf);
pos = 2;
/* Sequence number */
@ -460,6 +464,28 @@ frame802154_create(frame802154_t *p, uint8_t *buf)
return (int)pos;
}
void
frame802154_parse_fcf(uint8_t *data, frame802154_fcf_t *pfcf)
{
frame802154_fcf_t fcf;
/* decode the FCF */
fcf.frame_type = data[0] & 7;
fcf.security_enabled = (data[0] >> 3) & 1;
fcf.frame_pending = (data[0] >> 4) & 1;
fcf.ack_required = (data[0] >> 5) & 1;
fcf.panid_compression = (data[0] >> 6) & 1;
fcf.sequence_number_suppression = data[1] & 1;
fcf.ie_list_present = (data[1] >> 1) & 1;
fcf.dest_addr_mode = (data[1] >> 2) & 3;
fcf.frame_version = (data[1] >> 4) & 3;
fcf.src_addr_mode = (data[1] >> 6) & 3;
/* copy fcf */
memcpy(pfcf, &fcf, sizeof(frame802154_fcf_t));
}
/*----------------------------------------------------------------------------*/
/**
* \brief Parses an input frame. Scans the input frame to find each
@ -489,19 +515,7 @@ frame802154_parse(uint8_t *data, int len, frame802154_t *pf)
p = data;
/* decode the FCF */
fcf.frame_type = p[0] & 7;
fcf.security_enabled = (p[0] >> 3) & 1;
fcf.frame_pending = (p[0] >> 4) & 1;
fcf.ack_required = (p[0] >> 5) & 1;
fcf.panid_compression = (p[0] >> 6) & 1;
fcf.sequence_number_suppression = p[1] & 1;
fcf.ie_list_present = (p[1] >> 1) & 1;
fcf.dest_addr_mode = (p[1] >> 2) & 3;
fcf.frame_version = (p[1] >> 4) & 3;
fcf.src_addr_mode = (p[1] >> 6) & 3;
/* copy fcf and seqNum */
frame802154_parse_fcf(p, &fcf);
memcpy(&pf->fcf, &fcf, sizeof(frame802154_fcf_t));
p += 2; /* Skip first two bytes */

View file

@ -207,8 +207,10 @@ typedef struct {
/* Prototypes */
int frame802154_hdrlen(frame802154_t *p);
void frame802154_create_fcf(frame802154_fcf_t *fcf, uint8_t *buf);
int frame802154_create(frame802154_t *p, uint8_t *buf);
int frame802154_parse(uint8_t *data, int length, frame802154_t *pf);
void frame802154_parse_fcf(uint8_t *data, frame802154_fcf_t *pfcf);
/* Get current PAN ID */
uint16_t frame802154_get_pan_id(void);

View file

@ -1,8 +1,8 @@
# IEEE 802.15.4e TSCH (TimeSlotted Channel Hopping)
# IEEE 802.15.4-2015 TSCH and IETF 6TiSCH
## Overview
TSCH is a MAC layer of the [IEEE 802.15.4e-2012 amendment][ieee802.15.4e-2012],
Time Slotted Channel Hopping (TSCH) is a MAC layer of the [IEEE 802.15.4e-2012 amendment][ieee802.15.4e-2012],
currently being integrated as part of the new IEEE 802.15.4-2015.
[6TiSCH][ietf-6tisch-wg] is an IETF Working Group focused on IPv6 over TSCH.
This is a Contiki implementation of TSCH and the 6TiSCH so-called "minimal configuration",
@ -13,7 +13,9 @@ It was developped by:
* Beshr Al Nahas, SICS (now Chalmers University), beshr@chalmers.se, github user: [beshrns](https://github.com/beshrns)
* Atis Elsts, Univ. Bristol, atis.elsts@bristol.ac.uk, github user: [atiselsts](https://github.com/atiselsts)
You can find an extensive evaluation of this implementation in our paper [*Orchestra: Robust Mesh Networks Through Autonomously Scheduled TSCH*](http://www.simonduquennoy.net/papers/duquennoy15orchestra.pdf), ACM SenSys'15.
This implementation is presented in depth and evaluated in our paper: [*TSCH and 6TiSCH for Contiki: Challenges, Design and Evaluation*](http://www.simonduquennoy.net/papers/duquennoy17tsch.pdf), IEEE DCOSS'17.
The scheduler Orchestra is detailled in [*Orchestra: Robust Mesh Networks Through Autonomously Scheduled TSCH*](http://www.simonduquennoy.net/papers/duquennoy15orchestra.pdf), ACM SenSys'15.
## Features
@ -27,7 +29,7 @@ This implementation includes:
* Standard TSCH link selection and slot operation (10ms slots by default)
* Standard TSCH synchronization, including with ACK/NACK time correction Information Element
* Standard TSCH queues and CSMA-CA mechanism
* Standard TSCH security
* Standard TSCH and 6TiSCH security
* Standard 6TiSCH TSCH-RPL interaction (6TiSCH Minimal Configuration and Minimal Schedule)
* A scheduling API to add/remove slotframes and links
* A system for logging from TSCH timeslot operation interrupt, with postponed printout

View file

@ -202,6 +202,7 @@ tsch_queue_flush_nbr_queue(struct tsch_neighbor *n)
/* Free packet queuebuf */
tsch_queue_free_packet(p);
}
PRINTF("TSCH-queue: packet is deleted packet=%p\n", p);
}
}
/*---------------------------------------------------------------------------*/
@ -253,6 +254,8 @@ tsch_queue_add_packet(const linkaddr_t *addr, mac_callback_t sent, void *ptr)
/* Add to ringbuf (actual add committed through atomic operation) */
n->tx_array[put_index] = p;
ringbufindex_put(&n->tx_ringbuf);
PRINTF("TSCH-queue: packet is added put_index=%u, packet=%p\n",
put_index, p);
return p;
} else {
memb_free(&packet_memb, p);
@ -288,6 +291,7 @@ tsch_queue_remove_packet_from_queue(struct tsch_neighbor *n)
/* Get and remove packet from ringbuf (remove committed through an atomic operation */
int16_t get_index = ringbufindex_get(&n->tx_ringbuf);
if(get_index != -1) {
PRINTF("TSCH-queue: packet is removed, get_index=%u\n", get_index);
return n->tx_array[get_index];
} else {
return NULL;

View file

@ -99,13 +99,12 @@ create_dag_callback(void *ptr)
rpl_dag_t *dag;
dag = rpl_get_any_dag();
#if DEBUG
printf("Found a network we did not create\n");
printf("version %d grounded %d preference %d used %d joined %d rank %d\n",
PRINTF("RPL: Found a network we did not create\n");
PRINTF("RPL: version %d grounded %d preference %d used %d joined %d rank %d\n",
dag->version, dag->grounded,
dag->preference, dag->used,
dag->joined, dag->rank);
#endif /* DEBUG */
/* We found a RPL network that we did not create so we just join
it without becoming root. But if the network has an infinite
@ -223,14 +222,14 @@ rpl_dag_root_init_dag_immediately(void)
uip_ip6addr(&prefix, UIP_DS6_DEFAULT_PREFIX, 0, 0, 0, 0, 0, 0, 0);
rpl_set_prefix(dag, &prefix, 64);
PRINTF("rpl_dag_root_init_dag: created a new RPL dag\n");
PRINTF("RPL: rpl_dag_root_init_dag: created a new RPL dag\n");
return 0;
} else {
PRINTF("rpl_dag_root_init_dag: failed to create a new RPL DAG\n");
PRINTF("RPL: rpl_dag_root_init_dag: failed to create a new RPL DAG\n");
return -1;
}
} else {
PRINTF("rpl_dag_root_init_dag: failed to create a new RPL DAG, no preferred IP address found\n");
PRINTF("RPL: rpl_dag_root_init_dag: failed to create a new RPL DAG, no preferred IP address found\n");
return -2;
}
}

View file

@ -525,10 +525,10 @@ rpl_set_prefix(rpl_dag_t *dag, uip_ipaddr_t *prefix, unsigned len)
/* Autoconfigure an address if this node does not already have an address
with this prefix. Otherwise, update the prefix */
if(last_len == 0) {
PRINTF("rpl_set_prefix - prefix NULL\n");
PRINTF("RPL: rpl_set_prefix - prefix NULL\n");
check_prefix(NULL, &dag->prefix_info);
} else {
PRINTF("rpl_set_prefix - prefix NON-NULL\n");
PRINTF("RPL: rpl_set_prefix - prefix NON-NULL\n");
check_prefix(&last_prefix, &dag->prefix_info);
}
return 1;
@ -983,7 +983,7 @@ rpl_move_parent(rpl_dag_t *dag_src, rpl_dag_t *dag_dst, rpl_parent_t *parent)
PRINTF("RPL: Removing default route ");
PRINT6ADDR(rpl_get_parent_ipaddr(parent));
PRINTF("\n");
PRINTF("rpl_move_parent\n");
PRINTF("RPL: rpl_move_parent\n");
uip_ds6_defrt_rm(dag_src->instance->def_route);
dag_src->instance->def_route = NULL;
}
@ -1546,7 +1546,7 @@ rpl_process_dio(uip_ipaddr_t *from, rpl_dio_t *dio)
/* The DIO comes from a valid DAG, we can refresh its lifetime */
dag->lifetime = (1UL << (instance->dio_intmin + instance->dio_intdoubl)) * RPL_DAG_LIFETIME / 1000;
PRINTF("Set dag ");
PRINTF("RPL: Set dag ");
PRINT6ADDR(&dag->dag_id);
PRINTF(" lifetime to %ld\n", dag->lifetime);

View file

@ -507,10 +507,10 @@ update_hbh_header(void)
if((UIP_EXT_HDR_OPT_RPL_BUF->flags & RPL_HDR_OPT_DOWN)) {
if(uip_ds6_route_lookup(&UIP_IP_BUF->destipaddr) == NULL) {
UIP_EXT_HDR_OPT_RPL_BUF->flags |= RPL_HDR_OPT_FWD_ERR;
PRINTF("RPL forwarding error\n");
PRINTF("RPL: Forwarding error\n");
/* We should send back the packet to the originating parent,
but it is not feasible yet, so we send a No-Path DAO instead */
PRINTF("RPL generate No-Path DAO\n");
PRINTF("RPL: Generate No-Path DAO\n");
parent = rpl_get_parent((uip_lladdr_t *)packetbuf_addr(PACKETBUF_ADDR_SENDER));
if(parent != NULL) {
dao_output_target(parent, &UIP_IP_BUF->destipaddr, RPL_ZERO_LIFETIME);
@ -526,11 +526,11 @@ update_hbh_header(void)
/* No route was found, so this packet will go towards the RPL
root. If so, we should not set the down flag. */
UIP_EXT_HDR_OPT_RPL_BUF->flags &= ~RPL_HDR_OPT_DOWN;
PRINTF("RPL option going up\n");
PRINTF("RPL: Option going up\n");
} else {
/* A DAO route was found so we set the down flag. */
UIP_EXT_HDR_OPT_RPL_BUF->flags |= RPL_HDR_OPT_DOWN;
PRINTF("RPL option going down\n");
PRINTF("RPL: Option going down\n");
}
}
}
@ -644,11 +644,17 @@ rpl_update_header(void)
/* At the root, remove headers if any, and insert SRH or HBH
* (SRH is inserted only if the destination is in the DODAG) */
rpl_remove_header();
if(rpl_get_dag(&UIP_IP_BUF->destipaddr) != NULL) {
/* dest is in a DODAG; the packet is going down. */
if(RPL_IS_NON_STORING(default_instance)) {
return insert_srh_header();
} else {
return insert_hbh_header(default_instance);
}
} else {
/* dest is outside of DODAGs; no ext header is needed. */
return 1;
}
} else {
if(uip_ds6_is_my_addr(&UIP_IP_BUF->srcipaddr)
&& UIP_IP_BUF->ttl == uip_ds6_if.cur_hop_limit) {

View file

@ -158,8 +158,8 @@ get_global_addr(uip_ipaddr_t *addr)
static uint32_t
get32(uint8_t *buffer, int pos)
{
return (uint32_t)buffer[pos] << 24 | (uint32_t)buffer[pos + 1] << 16 |
(uint32_t)buffer[pos + 2] << 8 | buffer[pos + 3];
return ((uint32_t)buffer[pos] << 24 | (uint32_t)buffer[pos + 1] << 16 |
(uint32_t)buffer[pos + 2] << 8 | buffer[pos + 3]);
}
/*---------------------------------------------------------------------------*/
static void
@ -218,15 +218,14 @@ dis_input(void)
for(instance = &instance_table[0], end = instance + RPL_MAX_INSTANCES;
instance < end; ++instance) {
if(instance->used == 1) {
if(uip_is_addr_mcast(&UIP_IP_BUF->destipaddr)) {
#if RPL_LEAF_ONLY
if(!uip_is_addr_mcast(&UIP_IP_BUF->destipaddr)) {
PRINTF("RPL: LEAF ONLY Multicast DIS will NOT reset DIO timer\n");
#else /* !RPL_LEAF_ONLY */
if(uip_is_addr_mcast(&UIP_IP_BUF->destipaddr)) {
PRINTF("RPL: Multicast DIS => reset DIO timer\n");
rpl_reset_dio_timer(instance);
} else {
#endif /* !RPL_LEAF_ONLY */
} else {
/* Check if this neighbor should be added according to the policy. */
if(rpl_icmp6_update_nbr_table(&UIP_IP_BUF->srcipaddr,
NBR_TABLE_REASON_RPL_DIS, NULL) == NULL) {
@ -653,6 +652,7 @@ dao_input_storing(void)
prefixlen = 0;
parent = NULL;
memset(&prefix, 0, sizeof(prefix));
uip_ipaddr_copy(&dao_sender_addr, &UIP_IP_BUF->srcipaddr);
@ -749,6 +749,11 @@ dao_input_storing(void)
#if RPL_WITH_MULTICAST
if(uip_is_addr_mcast_global(&prefix)) {
/*
* "rep" is used for a unicast route which we don't need now; so set NULL so
* that operations on "rep" will be skipped.
*/
rep = NULL;
mcast_group = uip_mcast6_route_add(&prefix);
if(mcast_group) {
mcast_group->dag = dag;
@ -845,6 +850,7 @@ fwd_dao:
int should_ack = 0;
if(flags & RPL_DAO_K_FLAG) {
if(rep != NULL) {
/*
* check if this route is already installed and we can ack now!
* not pending - and same seq-no means that we can ack.
@ -857,10 +863,12 @@ fwd_dao:
should_ack = 1;
}
}
}
if(dag->preferred_parent != NULL &&
rpl_get_parent_ipaddr(dag->preferred_parent) != NULL) {
uint8_t out_seq = 0;
if(rep != NULL) {
/* if this is pending and we get the same seq no it is a retrans */
if(RPL_ROUTE_IS_DAO_PENDING(rep) &&
rep->state.dao_seqno_in == sequence) {
@ -869,6 +877,7 @@ fwd_dao:
} else {
out_seq = prepare_for_dao_fwd(sequence, rep);
}
}
PRINTF("RPL: Forwarding DAO to parent ");
PRINT6ADDR(rpl_get_parent_ipaddr(dag->preferred_parent));
@ -1142,30 +1151,30 @@ dao_output_target_seq(rpl_parent_t *parent, uip_ipaddr_t *prefix,
}
if(parent == NULL) {
PRINTF("RPL dao_output_target error parent NULL\n");
PRINTF("RPL: dao_output_target error parent NULL\n");
return;
}
parent_ipaddr = rpl_get_parent_ipaddr(parent);
if(parent_ipaddr == NULL) {
PRINTF("RPL dao_output_target error parent IP address NULL\n");
PRINTF("RPL: dao_output_target error parent IP address NULL\n");
return;
}
dag = parent->dag;
if(dag == NULL) {
PRINTF("RPL dao_output_target error dag NULL\n");
PRINTF("RPL: dao_output_target error dag NULL\n");
return;
}
instance = dag->instance;
if(instance == NULL) {
PRINTF("RPL dao_output_target error instance NULL\n");
PRINTF("RPL: dao_output_target error instance NULL\n");
return;
}
if(prefix == NULL) {
PRINTF("RPL dao_output_target error prefix NULL\n");
PRINTF("RPL: dao_output_target error prefix NULL\n");
return;
}
#ifdef RPL_DEBUG_DAO_OUTPUT

View file

@ -177,7 +177,7 @@ find_removable_dis(uip_ipaddr_t *from)
if(num_free > 0) {
/* there are free entries (e.g. unsused by RPL and ND6) but since it is
used by other modules we can not pick these entries for removal. */
PRINTF("Num-free > 0 = %d - Other for RPL/ND6 unused NBR entry exists .",
PRINTF("NBR-POLICY: Num-free > 0 = %d - Other for RPL/ND6 unused NBR entry exists .",
num_free);
}
if(num_children < MAX_CHILDREN) {
@ -195,20 +195,20 @@ find_removable_dio(uip_ipaddr_t *from, rpl_dio_t *dio)
instance = rpl_get_instance(dio->instance_id);
if(instance == NULL || instance->current_dag == NULL) {
PRINTF("Did not find instance id: %d\n", dio->instance_id);
PRINTF("NBR-POLICY: Did not find instance id: %d\n", dio->instance_id);
return NULL;
}
/* Add the new neighbor only if it is better than the worst parent. */
if(dio->rank + instance->min_hoprankinc < worst_rank - instance->min_hoprankinc / 2) {
/* Found *great* neighbor - add! */
PRINTF("Found better neighbor %d < %d - add to cache...\n",
PRINTF("NBR-POLICY: Found better neighbor %d < %d - add to cache...\n",
dio->rank, worst_rank);
return worst_rank_nbr;
}
PRINTF("Found worse neighbor with new %d and old %d - NOT add to cache.\n",
PRINTF("NBR-POLICY: Found worse neighbor with new %d and old %d - NOT add to cache.\n",
dio->rank, worst_rank);
return NULL;
}
@ -229,7 +229,7 @@ find_removable_dao(uip_ipaddr_t *from, rpl_instance_t *instance)
/* Check if this DAO sender is not yet neighbor and there is already too
many children. */
if(num_children >= max) {
PRINTF("Can not add another child - already at max.\n");
PRINTF("NBR-POLICY: Can not add another child - already at max.\n");
return NULL;
}
/* remove the worst ranked nbr */

View file

@ -91,13 +91,13 @@ rpl_set_mode(enum rpl_mode m)
PRINTF("RPL: switching to feather mode\n");
if(default_instance != NULL) {
PRINTF("rpl_set_mode: RPL sending DAO with zero lifetime\n");
PRINTF("RPL: rpl_set_mode: RPL sending DAO with zero lifetime\n");
if(default_instance->current_dag != NULL) {
dao_output(default_instance->current_dag->preferred_parent, RPL_ZERO_LIFETIME);
}
rpl_cancel_dao(default_instance);
} else {
PRINTF("rpl_set_mode: no default instance\n");
PRINTF("RPL: rpl_set_mode: no default instance\n");
}
mode = m;
@ -143,7 +143,7 @@ rpl_purge_routes(void)
uip_ipaddr_copy(&prefix, &r->ipaddr);
uip_ds6_route_rm(r);
r = uip_ds6_route_head();
PRINTF("No more routes to ");
PRINTF("RPL: No more routes to ");
PRINT6ADDR(&prefix);
dag = default_instance->current_dag;
/* Propagate this information with a No-Path DAO to preferred parent if we are not a RPL Root */
@ -313,7 +313,7 @@ rpl_purge_dags(void)
if(instance->dag_table[i].used) {
if(instance->dag_table[i].lifetime == 0) {
if(!instance->dag_table[i].joined) {
PRINTF("Removing dag ");
PRINTF("RPL: Removing dag ");
PRINT6ADDR(&instance->dag_table[i].dag_id);
PRINTF("\n");
rpl_free_dag(&instance->dag_table[i]);
@ -331,7 +331,7 @@ void
rpl_init(void)
{
uip_ipaddr_t rplmaddr;
PRINTF("RPL started\n");
PRINTF("RPL: RPL started\n");
default_instance = NULL;
rpl_dag_init();

View file

@ -68,7 +68,6 @@ typedef unsigned short uip_stats_t;
#define UIP_ARCH_ADD32 1
#define UIP_ARCH_CHKSUM 1
#define UIP_CONF_LLH_LEN 14
#define RESOLV_CONF_SUPPORTS_MDNS 0
#define RESOLV_CONF_SUPPORTS_RECORD_EXPIRATION 0
@ -80,6 +79,12 @@ void logscr(const void *msg, unsigned len);
#define logscr(msg, len) write(STDERR_FILENO, msg, len)
#endif
#if WITH_SLIP
#define UIP_CONF_LLH_LEN 0
#else /* WITH_SLIP */
#define UIP_CONF_LLH_LEN 14
#endif /* WITH_SLIP */
#if MTU_SIZE
#define UIP_CONF_BUFFER_SIZE (UIP_LLH_LEN + MTU_SIZE)
#else /* MTU_SIZE */

View file

@ -31,6 +31,10 @@
# Author: Oliver Schmidt <ol.sc@web.de>
#
ifdef SLIP
DEFINES += WITH_SLIP
endif
.SUFFIXES:
CONTIKI_TARGET_DIRS = . lib sys
@ -39,7 +43,7 @@ CONTIKI_CPU_DIRS = . lib sys ctk net
CONTIKI_TARGET_SOURCEFILES += contiki-main.c
CONTIKI_CPU_SOURCEFILES += log.c error.c unload.c config.c ctk-mouse.c \
clock.c mtarch.c mtarch-asm.S lc-asm.S \
uip_arch.c ethernet-drv.c ethernet.c
uip_arch.c slip_arch.c ethernet-drv.c ethernet.c
ETHERNET_SOURCEFILES = cs8900a.S lan91c96.S w5100.S
@ -63,7 +67,7 @@ AR = ar65
# The apps coming with Contiki run even on a 0x100 byte stack.
ASFLAGS = -t $(TARGET)
CFLAGS += -t $(TARGET) -Or -W -unused-param
CFLAGS += -t $(TARGET) -Ors -W -unused-param
LDFLAGS = -t $(TARGET) -m contiki-$(TARGET).map -D __STACKSIZE__=0x200
AROPTS = a

View file

@ -6,7 +6,7 @@ cc65 compiler [http://cc65.github.io/cc65/](http://cc65.github.io/cc65/).
The Contiki network configuration for 6502-based targets is loaded from a
binary configuration file (by default named contiki.cfg). It has the following
format:
format for Ethernet:
- Bytes 1 - 4: IP Address (HiByte first)
- Bytes 5 - 8: Subnet Mask (HiByte first)
@ -15,10 +15,13 @@ format:
- Bytes 17 - 18: Ethernet card I/O address (LoByte first !)
- Bytes 19 - xx: Ethernet card driver name (ASCII / PETSCII)
An online Contiki configuration file generator is available at two sites:
It has the following format for SLIP (based on RS232 driver coming with cc65):
- [http://www.a2retrosystems.com/contiki.html](http://www.a2retrosystems.com/contiki.html)
- [http://contiki.cbm8bit.com](http://contiki.cbm8bit.com)
- Bytes 1 - 4: IP Address (HiByte first)
- Bytes 5 - 8: Subnet Mask (HiByte first)
- Bytes 9 - 12: Default Router (HiByte first)
- Bytes 13 - 16: DNS Server (HiByte first)
- Bytes 17 - 21: struct ser_params (see cc65 serial.h)
The build for 6502-based machines includes the 'disk' make goal which creates a
bootable floppy disk image containing the project binary, a sample
@ -32,6 +35,11 @@ make goal. The values of the high-level configuration macros are not tracked by
the build so a manual rebuild is necessary on any change. The following
high-level configuration macros may be set:
- WITH_SLIP
- Default: 0
- Purpose: Use SLIP (based on RS232 driver coming with cc65) instead of
Ethernet.
- MTU_SIZE
- Default: 1500
- Purpose: Set the Maximum Transfer Unit size.
@ -78,6 +86,10 @@ high-level configuration macros may be set:
- Default: 0
- Purpose: Enable CTK mouse support and load a mouse driver.
- STATIC_MOUSE
- Default: N/A
- Purpose: Link mouse driver statically instead of loading it dynamically.
- WITH_ARGS
- Default: 0
- Purpose: Enable support for contiki_argc / contiki_argv.

View file

@ -49,6 +49,15 @@ static uint8_t okay;
void
ctk_mouse_init(void)
{
#ifdef STATIC_MOUSE
okay = mouse_install(&mouse_def_callbacks, &STATIC_MOUSE) == MOUSE_ERR_OK;
if(okay) {
atexit((void (*)(void))mouse_uninstall);
}
#else /* STATIC_MOUSE */
struct mod_ctrl module_control = {cfs_read};
module_control.callerdata = cfs_open("contiki.mou", CFS_READ);
@ -65,6 +74,8 @@ ctk_mouse_init(void)
}
cfs_close(module_control.callerdata);
}
#endif /* STATIC_MOUSE */
}
/*-----------------------------------------------------------------------------------*/
unsigned short

View file

@ -42,6 +42,7 @@ choose(uint8_t max)
exit(0);
}
putchar('\n');
return val - '0';
}
/*-----------------------------------------------------------------------------------*/
@ -65,13 +66,13 @@ main(void)
d = choose(d) - 1;
#ifdef __APPLE2__
printf("\nSlot (1-7)\n");
printf("Slot (1-7)\n");
drivers[d].address += choose(7) * 0x10;
#endif
f = cfs_open("contiki.cfg", CFS_WRITE);
if(f == -1) {
printf("\nSaving Config - Error\n");
printf("Saving Config - Error\n");
return;
}
cfs_write(f, ipcfg, sizeof(ipcfg));
@ -79,6 +80,6 @@ main(void)
cfs_write(f, drivers[d].driver, strlen(drivers[d].driver));
cfs_close(f);
printf("\nSaving Config - Done\n");
printf("Saving Config - Done\n");
}
/*-----------------------------------------------------------------------------------*/

View file

@ -39,7 +39,24 @@
#include "cfs/cfs.h"
#include "sys/log.h"
#include "lib/error.h"
#include "net/ethernet-drv.h"
#include "lib/config.h"
struct {
uip_ipaddr_t hostaddr;
uip_ipaddr_t netmask;
uip_ipaddr_t draddr;
uip_ipaddr_t resolvaddr;
union {
struct {
uint16_t addr;
#ifndef STATIC_DRIVER
char name[12+1];
#endif /* !STATIC_DRIVER */
} ethernet;
uint8_t slip[5];
};
} config;
/*-----------------------------------------------------------------------------------*/
#if LOG_CONF_ENABLED
@ -59,16 +76,9 @@ ipaddrtoa(uip_ipaddr_t *ipaddr, char *buffer)
}
#endif /* LOG_CONF_ENABLED */
/*-----------------------------------------------------------------------------------*/
struct ethernet_config *
void
config_read(char *filename)
{
static struct {
uip_ipaddr_t hostaddr;
uip_ipaddr_t netmask;
uip_ipaddr_t draddr;
uip_ipaddr_t resolvaddr;
struct ethernet_config ethernetcfg;
} config;
int file;
file = cfs_open(filename, CFS_READ);
@ -77,8 +87,8 @@ config_read(char *filename)
error_exit();
}
if(cfs_read(file, &config, sizeof(config)) < sizeof(config)
- sizeof(config.ethernetcfg.name)) {
if(cfs_read(file, &config, sizeof(config)) < sizeof(uip_ipaddr_t) * 4
+ sizeof(uint16_t)) {
log_message(filename, ": No config file");
error_exit();
}
@ -90,16 +100,22 @@ config_read(char *filename)
log_message("Def. Router: ", ipaddrtoa(&config.draddr, uip_buf));
log_message("DNS Server: ", ipaddrtoa(&config.resolvaddr, uip_buf));
#ifndef STATIC_DRIVER
log_message("Eth. Driver: ", config.ethernetcfg.name);
#else /* !STATIC_DRIVER */
#ifdef STATIC_DRIVER
#define _stringize(arg) #arg
#define stringize(arg) _stringize(arg)
log_message("Eth. Driver: ", stringize(ETHERNET));
#if WITH_SLIP
log_message("SLIP Driver: ", stringize(STATIC_DRIVER));
#else /* WITH_SLIP */
log_message("Eth. Driver: ", stringize(STATIC_DRIVER));
#endif /* WITH_SLIP */
#undef _stringize
#undef stringize
#endif /* !STATIC_DRIVER */
log_message("Driver Port: $", utoa(config.ethernetcfg.addr, uip_buf, 16));
#else /* STATIC_DRIVER */
log_message("Eth. Driver: ", config.ethernet.name);
#endif /* STATIC_DRIVER */
#if !WITH_SLIP
log_message("Driver Port: $", utoa(config.ethernet.addr, uip_buf, 16));
#endif /* !WITH_SLIP */
uip_sethostaddr(&config.hostaddr);
uip_setnetmask(&config.netmask);
@ -107,7 +123,5 @@ config_read(char *filename)
#if WITH_DNS
uip_nameserver_update(&config.resolvaddr, UIP_NAMESERVER_INFINITE_LIFETIME);
#endif /* WITH_DNS */
return &config.ethernetcfg;
}
/*-----------------------------------------------------------------------------------*/

View file

@ -35,6 +35,22 @@
#ifndef CONFIG_H_
#define CONFIG_H_
struct ethernet_config * config_read(char *filename);
extern struct {
uip_ipaddr_t hostaddr;
uip_ipaddr_t netmask;
uip_ipaddr_t draddr;
uip_ipaddr_t resolvaddr;
union {
struct {
uint16_t addr;
#ifndef STATIC_DRIVER
char name[12+1];
#endif /* !STATIC_DRIVER */
} ethernet;
uint8_t slip[5];
};
} config;
void config_read(char *filename);
#endif /* CONFIG_H_ */

View file

@ -92,7 +92,7 @@ PROCESS_THREAD(ethernet_process, ev, data)
PROCESS_BEGIN();
ethernet_init((struct ethernet_config *)data);
ethernet_init();
tcpip_set_outputfunc(ethernet_output);

View file

@ -35,11 +35,6 @@
#include "contiki.h"
struct ethernet_config {
uint16_t addr;
char name[12+1];
};
PROCESS_NAME(ethernet_process);
#if NETSTACK_CONF_WITH_IPV6

View file

@ -38,7 +38,7 @@
#include "cfs/cfs.h"
#include "sys/log.h"
#include "lib/error.h"
#include "net/ethernet-drv.h"
#include "lib/config.h"
#include "net/ethernet.h"
@ -59,24 +59,41 @@ struct {
/*---------------------------------------------------------------------------*/
void
ethernet_init(struct ethernet_config *config)
ethernet_init(void)
{
static const char signature[4] = {0x65, 0x74, 0x68, 0x01};
#ifndef STATIC_DRIVER
#ifdef STATIC_DRIVER
extern void STATIC_DRIVER;
module = &STATIC_DRIVER;
module->buffer = uip_buf;
module->buffer_size = UIP_BUFSIZE;
if(module->init(config.ethernet.addr)) {
#define _stringize(arg) #arg
#define stringize(arg) _stringize(arg)
log_message(stringize(STATIC_DRIVER), ": No hardware");
#undef _stringize
#undef stringize
error_exit();
}
#else /* STATIC_DRIVER */
struct mod_ctrl module_control = {cfs_read};
uint8_t byte;
module_control.callerdata = cfs_open(config->name, CFS_READ);
module_control.callerdata = cfs_open(config.ethernet.name, CFS_READ);
if(module_control.callerdata < 0) {
log_message(config->name, ": File not found");
log_message(config.ethernet.name, ": File not found");
error_exit();
}
byte = mod_load(&module_control);
if(byte != MLOAD_OK) {
log_message(config->name, byte == MLOAD_ERR_MEM? ": Out of memory":
log_message(config.ethernet.name, byte == MLOAD_ERR_MEM? ": Out of memory":
": No module");
error_exit();
}
@ -86,26 +103,20 @@ ethernet_init(struct ethernet_config *config)
for(byte = 0; byte < 4; ++byte) {
if(module->signature[byte] != signature[byte]) {
log_message(config->name, ": No ETH driver");
log_message(config.ethernet.name, ": No ETH driver");
error_exit();
}
}
#else /* !STATIC_DRIVER */
extern void STATIC_DRIVER;
module = &STATIC_DRIVER;
#endif /* !STATIC_DRIVER */
module->buffer = uip_buf;
module->buffer_size = UIP_BUFSIZE;
if(module->init(config->addr)) {
log_message(config->name, ": No hardware");
if(module->init(config.ethernet.addr)) {
log_message(config.ethernet.name, ": No hardware");
error_exit();
}
#endif /* STATIC_DRIVER */
uip_setethaddr(module->ethernet_address);
}
/*---------------------------------------------------------------------------*/

View file

@ -35,7 +35,7 @@
#ifndef ETHERNET_H_
#define ETHERNET_H_
void ethernet_init(struct ethernet_config *config);
void ethernet_init(void);
uint16_t ethernet_poll(void);
void ethernet_send(void);
void ethernet_exit(void);

View file

@ -1,4 +1,7 @@
/*
* Copyright (c) 2017, Swedish Institute of Computer Science
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -25,43 +28,57 @@
*
* This file is part of the Contiki operating system.
*
* Author: Oliver Schmidt <ol.sc@web.de>
*
*/
/*
Author: Robert Olsson <robert@radio-sensors.com>
*/
#include <serial.h>
#include <stdlib.h>
#include "contiki.h"
#include "net/rime/rime.h"
#include "random.h"
#include "dev/button-sensor.h"
#include "dev/leds.h"
#include <stdio.h>
#include "contiki-net.h"
#include "sys/log.h"
#include "lib/error.h"
#include "lib/config.h"
#include "dev/slip.h"
#if WITH_SLIP
/*---------------------------------------------------------------------------*/
PROCESS(sniffer_process, "Sniffer process");
AUTOSTART_PROCESSES(&sniffer_process);
/*---------------------------------------------------------------------------*/
PROCESS_THREAD(sniffer_process, ev, data)
void
slip_arch_init(unsigned long ubr)
{
PROCESS_BEGIN();
unsigned err;
/*
To get rf230bb radio in sniff mode we need to have radio in RX_ON.
The promisc commands fixes this for us. No need to set PAN and
address or MAC to zero is this case. Se Atmel datasheet. There is
a chance other radios works the same way.
*/
rf230_set_promiscuous_mode(1);
printf("Sniffer started\n");
while(1) {
PROCESS_YIELD();
err = ser_install(STATIC_DRIVER);
if(err == SER_ERR_OK) {
err = ser_open((struct ser_params *)config.slip);
if(err == SER_ERR_OK)
atexit((void (*)(void))ser_close);
}
if(err != SER_ERR_OK) {
err += '0';
/* High byte of err serves as string termination. */
log_message("Serial init error code: ", (char *)&err);
error_exit();
}
PROCESS_END();
tcpip_set_outputfunc(slip_send);
}
/*---------------------------------------------------------------------------*/
void
slip_arch_writeb(unsigned char c)
{
while(ser_put(c) == SER_ERR_OVERFLOW)
;
}
/*---------------------------------------------------------------------------*/
void
slip_arch_poll(void)
{
static unsigned char c;
while(ser_get(&c) != SER_ERR_NO_DATA)
slip_input_byte(c);
}
/*---------------------------------------------------------------------------*/
#endif /* WITH_SLIP */

View file

@ -0,0 +1,6 @@
CONTIKI_PROJECT = serconfig
all: $(CONTIKI_PROJECT)
CONTIKI = ../../..
CONTIKI_WITH_IPV4 = 1
include $(CONTIKI)/Makefile.include

View file

@ -0,0 +1 @@
DEFINES = WITH_PFS

View file

@ -0,0 +1 @@
DEFINES = WITH_PFS

View file

@ -0,0 +1,105 @@
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <serial.h>
#include "cfs/cfs.h"
static struct {
char *screen;
uint8_t value;
} baud[] = {
{" 300 baud", SER_BAUD_300},
{" 600 baud", SER_BAUD_600},
{" 1200 baud", SER_BAUD_1200},
{" 2400 baud", SER_BAUD_2400},
{" 4800 baud", SER_BAUD_4800},
{" 9600 baud", SER_BAUD_9600},
{"19200 baud", SER_BAUD_19200}
};
static struct {
char *screen;
uint8_t value;
} stop[] = {
{"1 stop bit", SER_STOP_1},
{"2 stop bits", SER_STOP_2}
};
static struct {
char *screen;
uint8_t value;
} parity[] = {
{" No parity", SER_PAR_NONE},
{" Odd parity", SER_PAR_ODD},
{"Even parity", SER_PAR_EVEN}
};
uint8_t ipcfg[16];
struct ser_params params;
/*-----------------------------------------------------------------------------------*/
uint8_t
choose(uint8_t max)
{
char val;
do {
printf("\n?");
val = getchar();
} while(val < '0' || val > max + '0');
putchar('\n');
if(val == '0') {
exit(0);
}
putchar('\n');
return val - '0';
}
/*-----------------------------------------------------------------------------------*/
void
main(void)
{
int f;
uint8_t c;
f = cfs_open("contiki.cfg", CFS_READ);
if(f == -1) {
printf("Loading Config - Error\n");
return;
}
cfs_read(f, ipcfg, sizeof(ipcfg));
cfs_close(f);
for(c = 0; c < sizeof(baud) / sizeof(baud[0]); ++c) {
printf("%d: %s\n", c + 1, baud[c].screen);
}
params.baudrate = baud[choose(c) - 1].value;
params.databits = SER_BITS_8;
for(c = 0; c < sizeof(stop) / sizeof(stop[0]); ++c) {
printf("%d: %s\n", c + 1, stop[c].screen);
}
params.stopbits = stop[choose(c) - 1].value;
for(c = 0; c < sizeof(parity) / sizeof(parity[0]); ++c) {
printf("%d: %s\n", c + 1, parity[c].screen);
}
params.parity = parity[choose(c) - 1].value;
params.handshake = SER_HS_HW;
f = cfs_open("contiki.cfg", CFS_WRITE);
if(f == -1) {
printf("\nSaving Config - Error\n");
return;
}
cfs_write(f, ipcfg, sizeof(ipcfg));
cfs_write(f, &params, sizeof(params));
cfs_close(f);
printf("Saving Config - Done\n");
}
/*-----------------------------------------------------------------------------------*/

View file

@ -236,6 +236,7 @@
#define RG_RX_SYN 0x15
/** Offset for register XAH_CTRL_1 */
#define RG_XAH_CTRL_1 0x17
#define SR_AACK_PROM_MODE 0x17, 0x02, 1
/** Access parameters for sub-register XTAL_MODE in register @ref RG_XOSC_CTRL */
#define SR_XTAL_MODE 0x12, 0xf0, 4
/** Access parameters for sub-register XTAL_TRIM in register @ref RG_XOSC_CTRL */
@ -340,6 +341,7 @@
#define SR_CSMA_SEED_0 0x2d, 0xff, 0
/** Offset for register CSMA_SEED_1 */
#define RG_CSMA_SEED_1 (0x2e)
#define SR_AACK_DIS_ACK 0x2e, 0x10, 4
/** Offset for register CSMA_BE */
#define RG_CSMA_BE 0x2f
/** Access parameters for sub-register MIN_BE in register @ref RG_CSMA_SEED_1 */

View file

@ -83,7 +83,28 @@
#define SR_CCA_DONE 0x141, 0x80, 7
#define SR_CCA_STATUS 0x141, 0x40, 6
#define SR_AACK_SET_PD 0x16e, 0x20, 5
#define SR_AACK_DIS_ACK 0x16e, 0x10, 4
#define RG_XAH_CTRL_1 (0x157)
#define SR_AACK_PROM_MODE 0x157, 0x02, 1
#define RG_AES_KEY (0x13F)
#define SR_AES_KEY 0x13F, 0xff, 0
#define RG_AES_STATE (0x13E)
#define SR_AES_STATE 0x13E, 0xff, 0
#define RG_AES_STATUS (0x13D)
#define SR_AES_STATUS 0x13D, 0xff, 0
#define SR_AES_STATUS_DONE 0x13D, 0x01, 0
#define SR_AES_STATUS_ERR 0x13D, 0x80, 7
#define RG_AES_CNTRL (0x13C)
#define SR_AES_CNTRL 0x13C, 0xff, 0
#define SR_AES_CNTRL_IM 0x13C, 0x04, 2
#define SR_AES_CNTRL_DIR 0x13C, 0x08, 3
#define SR_AES_CNTRL_MODE 0x13C, 0x20, 5
#define SR_AES_CNTRL_REQUEST 0x13C, 0x80, 7
#define SR_IRQ_MASK 0x14e, 0xff, 0
/* RF230 register assignments, for reference */
#if 0

View file

@ -41,6 +41,120 @@
* Registers can be read with a macro, but the args for subregisters don't expand properly so the actual address
* is used with explicit _SFR_MEM8 in the subregister read/write routines.
*/
/* Symbol Counter */
#define RG_SCCNTHH (0xE4) /* SCCNTHH7-0 */
#define RG_SCCNTHL (0xE3) /* SCCNTHL7-0 */
#define RG_SCCNTLH (0xE2) /* SCCNTLH7-0 */
#define RG_SCCNTLL (0xE1) /* SCCNTLL7-0 */
/* Counter control register 0 */
#define RG_SCCR0 (0xdc)
#define SR_SCCR0 0xdc, 0xff, 0
#define SR_SCCR0_SCRES 0xdc, 0x80, 7 /* Counter Sync. */
#define SR_SCCR0_SCMBTS 0xdc, 0x40, 6 /* Manual Beacon timestamp */
#define SR_SCCR0_SCEN 0xdc, 0x20, 5 /* Counter enable */
#define SR_SCCR0_SCCKSEL 0xdc, 0x10, 4 /* Counter clock source */
#define SR_SCCR0_SCTSE 0xdc, 0x08, 3 /* Auto timstamp Beacon, SFD */
#define SR_SCCR0_SCMP3 0xdc, 0x04, 2 /* Compare 3 counter mode sel. */
#define SR_SCCR0_SCMP2 0xdc, 0x02, 1 /* Compare 2 counter mode sel. */
#define SR_SCCR0_SCMP1 0xdc, 0x01, 0 /* Compare 1 counter mode sel. */
/* Counter control register 1 */
#define RG_SCCR1 (0xdd)
#define SR_SCCR1 0xdd, 0xff, 0
#define SR_SCCR1_SCBTSM 0xdd, 0x20, 5 /* Disable beacon timestamp */
#define SR_SCCR1_CLKDIV 0xdd, 0x1c, 2 /* CLKDIV */
#define SR_SCCR1_CLK0 0xdd, 0x10, 4 /* CLK0 */
#define SR_SCCR1_CLK1 0xdd, 0x08, 3 /* CLK1 */
#define SR_SCCR1_CLK2 0xdd, 0x04, 2 /* CLK2 */
#define SR_SCCR1_EECLK 0xdd, 0x02, 1 /* */
#define SR_SCCR1_SCENBO 0xdd, 0x01, 0 /* Backoff Slot Counter Enable */
/* Prescaler for symbol counter */
#define SCCKDIV_62_5k 0
#define SCCKDIV_125k 1
#define SCCKDIV_250k 2
#define SCCKDIV_500k 3
#define SCCKDIV_1M 4
#define SCCKDIV_2M 5
#define SCCKDIV_4M 6
/* Counter status register 1 */
#define RG_SCSR (0xde)
#define SR_SCSR 0xde, 0xff, 0
#define SR_SCBSY 0xde, 0x01, 0 /* Symbol counter busy */
/* Counter ISR */
#define RG_SCIRQS (0xe0)
#define SR_SCIRQS 0xe0, 0xff, 0
#define SR_SCIRQS_IRQSB0 0xe0, 0x10, 4 /* Backoff */
#define SR_SCIRQS_IRQSOF 0xe0, 0x08, 3 /* Counter overflow */
#define SR_SCIRQS_IRQSCP3 0xe0, 0x04, 2 /* Compare 3 counter */
#define SR_SCIRQS_IRQSCP2 0xe0, 0x02, 1 /* Compare 2 counter */
#define SR_SCIRQS_IRQSCP1 0xe0, 0x01, 0 /* Compare 1 counter */
/* Counter IRQ mask */
#define RG_SCIRQM (0xdf)
#define SR_SCIRQM 0xdf, 0xff, 0
#define SR_SCIRQM_IRQMB0 0xdf, 0x10, 4 /* Backoff mask */
#define SR_SCIRQM_IRQMOF 0xdf, 0x08, 3 /* Counter overflow mask */
#define SR_SCIRQM_IRQMCP3 0xdf, 0x04, 2 /* Compare 3 counter mask */
#define SR_SCIRQM_IRQMCP2 0xdf, 0x02, 1 /* Compare 2 counter mask */
#define SR_SCIRQM_IRQMCP1 0xdf, 0x01, 0 /* Compare 1 counter mask */
/* Timestamp SFD */
#define RG_SCTSRHH 0xFC /* SCTSRHH7-0 */
#define RG_SCTSRHL 0xFB /* SCTSRHL7-0 */
#define RG_SCTSRLH 0xFA /* SCTSRLH7-0 */
#define RG_SCTSRLL 0xF9 /* SCTSRLL7-0 */
/* Beacon Timestamp */
#define RG_SCBTSRHH (0xE8) /* SCBTSRHH7-0 */
#define RG_SCBTSRHL (0xE7) /* SCBTSRHL7-0 */
#define RG_SCBTSRLH (0xE6) /* SCBTSRLH7-0 */
#define RG_SCBTSRLL (0xE5) /* SCBTSRLL7-0 */
/* Output Compare 1 */
#define RG_SCOCR1HH (0xF8) /* SCOCR1HH7-0 */
#define RG_SCOCR1HL (0xF7) /* SCOCR1HL7-0 */
#define RG_SCOCR1LH (0xF6) /* SCOCR1LH7-0 */
#define RG_SCOCR1LL (0xF5) /* SCOCR1LL7-0 */
/* Output Compare 2 */
#define RG_SCOCR2HH (0xF4) /* SCOCR2HH7-0 */
#define RG_SCOCR2HL (0xF3) /* SCOCR2HL7-0 */
#define RG_SCOCR2LH (0xF2) /* SCOCR2LH7-0 */
#define RG_SCOCR2LL (0xF1) /* SCOCR2LL7-0 */
/* Output Compare 3 */
#define RG_SCOCR3HH (0xF0) /* SCOCR3HH7-0 */
#define RG_SCOCR3HL (0xEF) /* SCOCR3HL7-0 */
#define RG_SCOCR3LH (0xEE) /* SCOCR3LH7-0 */
#define RG_SCOCR3LL (0xED) /* SCOCR3LL7-0 */
/* Transmit Frame Timestamp */
#define RG_SCTSTRHH (0xFC) /* SCTSTRHH7-0 */
#define RG_SCTSTRHL (0xFB) /* SCTSTRHL7-0 */
#define RG_SCTSTRLH (0xFA) /* SCTSTRLH7-0 */
#define RG_SCTSTRLL (0xF9) /* SCTSTRLL7-0 */
/*
Interrupt Status
#define RG_SCIRQS (0xE0) Res2 Res1 Res0 IRQSBO IRQSOF IRQSCP3 IRQSCP2 IRQSCP1 page 173
Interrupt Mask
#define RG_SCIRQM (0xDF) Res2 Res1 Res0 IRQMBO IRQMOF IRQMCP3 IRQMCP2 IRQMCP1 page 174
Counter status
#define RG_SCSR (0xDE) Res6 Res5 Res4 Res3 Res2 Res1 Res0 SCBSY page 173
Counter Control 1
#define RG_SCCR1 (0xDD) Res6 Res5 SCBTSM SCCKDIV2 SCCKDIV1 SCCKDIV0 SCEECLK SCENBO page 172
Counter Control 0
#define RG_SCCR0 (0xDC) SCRES SCMBTS SCEN SCCKSEL SCTSE SCCMP3 SCCMP2 SCCMP1 page 171
Counter Compare Source
#define RG_SCCSR (0xDB) Res1 Res0 SCCS31 SCCS30 SCCS21 SCCS20 SCCS11 SCCS10 page 161
*/
#define RG_TRX_STATUS TRX_STATUS
#define SR_TRX_STATUS 0x141, 0x1f, 0
#define SR_TRX_CMD 0x142, 0x1f, 0
@ -48,9 +162,35 @@
#define SR_TX_PWR 0x145, 0x0f, 0
#define RG_VERSION_NUM VERSION_NUM
#define RG_MAN_ID_0 MAN_ID_0
#define RG_IRQ_MASK IRQ_MASK
#define RG_IRQ_MASK (0x14e)
/** Access parameters for sub-register IRQ_MASK in register @ref RG_IRQ_MASK */
#define SR_IRQ_MASK 0x14e, 0xff, 0
/** Offset for register IRQ_STATUS */
#define RG_IRQ_STATUS (0x14f)
#define SR_IRQ_STATUS 0x14f, 0xff, 0
/** Awake Interrupt Status */
#define SR_IRQ_AWAKE 0x14f, 0x80, 7
/** TX_END Interrupt Status */
#define SR_IRQ_TX_END 0x14f, 0x40, 6
/** Address Match */
#define SR_IRQ_AMI 0x14f, 0x20, 5
/** End of ED Measurement Interrupt Status */
#define SR_CCA_ED_DONE 0x14f, 0x10, 4
/** Access parameters for sub-register IRQ_3_TRX_END in register @ref RG_IRQ_STATUS */
#define SR_IRQ_3_TRX_END 0x14f, 0x08, 3
/** Access parameters for sub-register IRQ_2_RX_START in register @ref RG_IRQ_STATUS */
#define SR_IRQ_2_RX_START 0x14f, 0x04, 2
/** Access parameters for sub-register IRQ_1_PLL_UNLOCK in register @ref RG_IRQ_STATUS */
#define SR_IRQ_1_PLL_UNLOCK 0x14f, 0x02, 1
/** Access parameters for sub-register IRQ_0_PLL_LOCK in register @ref RG_IRQ_STATUS */
#define RG_XAH_CTRL_1 (0x157)
#define SR_AACK_PROM_MODE 0x157, 0x02, 1
#define SR_IRQ_0_PLL_LOCK 0x14f, 0x01, 0
#define SR_MAX_FRAME_RETRIES 0x16C, 0xf0, 4
#define SR_TX_AUTO_CRC_ON 0x144, 0x20, 5
#define SR_PLL_FLT 0x144, 0x10, 4
#define SR_TRAC_STATUS 0x142, 0xe0, 5
#define SR_CHANNEL 0x148, 0x1f, 0
#define SR_CCA_MODE 0x148, 0x60, 5
@ -67,7 +207,7 @@
#define RG_IEEE_ADDR_5 IEEE_ADDR_5
#define RG_IEEE_ADDR_6 IEEE_ADDR_6
#define RG_IEEE_ADDR_7 IEEE_ADDR_7
//#define SR_ED_LEVEL 0x147, 0xff, 0
/* #define SR_ED_LEVEL 0x147, 0xff, 0 */
#define RG_PHY_ED_LEVEL PHY_ED_LEVEL
#define RG_RX_SYN RX_SYN
#define SR_RSSI 0x146, 0x1f, 0
@ -81,12 +221,28 @@
#define RG_CSMA_BE CSMA_BE
#define RG_CSMA_SEED_0 CSMA_SEED_0
#define RG_PHY_RSSI PHY_RSSI
//#define SR_CCA_CS_THRES 0x149, 0xf0, 4
#define SR_CCA_CS_THRES 0x149, 0xf0, 4
#define SR_CCA_ED_THRES 0x149, 0x0f, 0
#define SR_CCA_DONE 0x141, 0x80, 7
#define SR_CCA_STATUS 0x141, 0x40, 6
#define SR_AACK_SET_PD 0x16e, 0x20, 5
#define SR_CSMA_SEED_1 0x16e, 0x10, 4
#define SR_CSMA_SEED_1 0x16e, 0x03, 0
#define SR_AACK_DIS_ACK 0x16e, 0x10, 4
#define RG_AES_KEY (0x13F)
#define SR_AES_KEY 0x13F, 0xff, 0
#define RG_AES_STATE (0x13E)
#define SR_AES_STATE 0x13E, 0xff, 0
#define RG_AES_STATUS (0x13D)
#define SR_AES_STATUS 0x13D, 0xff, 0
#define SR_AES_STATUS_DONE 0x13D, 0x01, 0
#define SR_AES_STATUS_ERR 0x13D, 0x80, 7
#define RG_AES_CNTRL (0x13C)
#define SR_AES_CNTRL 0x13C, 0xff, 0
#define SR_AES_CNTRL_IM 0x13C, 0x04, 2
#define SR_AES_CNTRL_DIR 0x13C, 0x08, 3
#define SR_AES_CNTRL_MODE 0x13C, 0x20, 5
#define SR_AES_CNTRL_REQUEST 0x13C, 0x80, 7
/* RF230 register assignments, for reference */
#if 1
@ -216,27 +372,6 @@
///** Access parameters for sub-register CCA_ED_THRES in register @ref RG_CCA_THRES */
//#define SR_CCA_ED_THRES 0x09, 0x0f, 0
///** Offset for register IRQ_MASK */
//#define RG_IRQ_MASK (0x0e)
///** Access parameters for sub-register IRQ_MASK in register @ref RG_IRQ_MASK */
//#define SR_IRQ_MASK 0x0e, 0xff, 0
///** Offset for register IRQ_STATUS */
//#define RG_IRQ_STATUS (0x0f)
///** Access parameters for sub-register IRQ_7_BAT_LOW in register @ref RG_IRQ_STATUS */
//#define SR_IRQ_7_BAT_LOW 0x0f, 0x80, 7
///** Access parameters for sub-register IRQ_6_TRX_UR in register @ref RG_IRQ_STATUS */
//#define SR_IRQ_6_TRX_UR 0x0f, 0x40, 6
///** Access parameters for sub-register IRQ_5 in register @ref RG_IRQ_STATUS */
//#define SR_IRQ_5 0x0f, 0x20, 5
///** Access parameters for sub-register IRQ_4 in register @ref RG_IRQ_STATUS */
//#define SR_IRQ_4 0x0f, 0x10, 4
///** Access parameters for sub-register IRQ_3_TRX_END in register @ref RG_IRQ_STATUS */
//#define SR_IRQ_3_TRX_END 0x0f, 0x08, 3
///** Access parameters for sub-register IRQ_2_RX_START in register @ref RG_IRQ_STATUS */
//#define SR_IRQ_2_RX_START 0x0f, 0x04, 2
///** Access parameters for sub-register IRQ_1_PLL_UNLOCK in register @ref RG_IRQ_STATUS */
//#define SR_IRQ_1_PLL_UNLOCK 0x0f, 0x02, 1
///** Access parameters for sub-register IRQ_0_PLL_LOCK in register @ref RG_IRQ_STATUS */
//#define SR_IRQ_0_PLL_LOCK 0x0f, 0x01, 0
///** Offset for register VREG_CTRL */
//#define RG_VREG_CTRL (0x10)
///** Access parameters for sub-register AVREG_EXT in register @ref RG_VREG_CTRL */

View file

@ -81,10 +81,10 @@ extern uint8_t debugflowsize,debugflow[DEBUGFLOWSIZE];
#include "at86rf230_registermap.h"
#endif
extern void rf230_get_last_rx_packet_timestamp(void);
/*============================ VARIABLES =====================================*/
volatile extern signed char rf230_last_rssi;
/*============================ CALLBACKS =====================================*/
@ -669,7 +669,7 @@ ISR(TRX24_RX_START_vect)
#if !RF230_CONF_AUTOACK
rf230_last_rssi = 3 * hal_subregister_read(SR_RSSI);
#endif
rf230_get_last_rx_packet_timestamp();
}
/* PLL has locked, either from a transition out of TRX_OFF or a channel change while on */

View file

@ -46,6 +46,7 @@
#if defined(__AVR__)
#include <avr/io.h>
#include <dev/watchdog.h>
//_delay_us has the potential to use floating point which brings the 256 byte clz table into RAM
//#include <util/delay.h>
@ -94,6 +95,9 @@
static bool is_promiscuous;
#endif
/* Poll mode disabled by default */
uint8_t poll_mode = 0;
/* RF230_CONF_FRAME_RETRIES is 1 plus the number written to the hardware. */
/* Valid range 1-16, zero disables extended mode. */
#ifndef RF230_CONF_FRAME_RETRIES
@ -143,6 +147,8 @@ uint8_t ack_pending,ack_seqnum;
#warning RF230 Untested Configuration!
#endif
static rtimer_clock_t rf230_last_rx_packet_timestamp;
struct timestamp {
uint16_t time;
uint8_t authority_level;
@ -201,6 +207,8 @@ extern uint8_t debugflowsize,debugflow[DEBUGFLOWSIZE];
#define DEBUGFLOW(c)
#endif
static radio_status_t radio_set_trx_state(uint8_t new_state);
/* XXX hack: these will be made as Chameleon packet attributes */
#if RF230_CONF_TIMESTAMPS
rtimer_clock_t rf230_time_of_arrival, rf230_time_of_departure;
@ -254,22 +262,265 @@ static int rf230_cca(void);
uint8_t rf230_last_correlation,rf230_last_rssi,rf230_smallest_rssi;
static void
set_poll_mode(bool enable)
{
poll_mode = enable;
if(poll_mode) {
rf230_set_rpc(0x0); /* Disbable all RPC features */
radio_set_trx_state(RX_ON);
hal_subregister_write(SR_IRQ_MASK, RF230_SUPPORTED_INTERRUPT_MASK);
/* hal_register_write(RG_IRQ_MASK, 0xFF); */
} else {
/* Initialize and enable interrupts */
rf230_set_rpc(0xFF); /* Enable all RPC features. Only XRFR2 radios */
radio_set_trx_state(RX_AACK_ON);
}
}
static bool
get_poll_mode(void)
{
return poll_mode;
}
static void
set_frame_filtering(bool i)
{
if(i)
hal_subregister_write(SR_AACK_PROM_MODE, 0);
else {
hal_subregister_write(SR_AACK_PROM_MODE, 1);
}
}
static bool
get_frame_filtering(void)
{
int i = hal_subregister_read(SR_AACK_PROM_MODE);
if(i)
return 0;
return 1;
}
static void
set_auto_ack(bool i)
{
if(i)
hal_subregister_write(SR_AACK_DIS_ACK, 0);
else
hal_subregister_write(SR_AACK_DIS_ACK, 1);
}
static bool
get_auto_ack(void)
{
int i = hal_subregister_read(SR_AACK_DIS_ACK);
if(i)
return 0;
return 1;
}
uint16_t
rf230_get_panid(void)
{
unsigned pan;
uint8_t byte;
byte = hal_register_read(RG_PAN_ID_1);
pan = byte;
byte = hal_register_read(RG_PAN_ID_0);
pan = (pan << 8) + byte;
return pan;
}
static void
rf230_set_panid(uint16_t pan)
{
hal_register_write(RG_PAN_ID_1, (pan >> 8));
hal_register_write(RG_PAN_ID_0, (pan & 0xFF));
}
static uint16_t
rf230_get_short_addr(void)
{
unsigned char a0, a1;
a0 = hal_register_read(RG_SHORT_ADDR_0);
a1 = hal_register_read(RG_SHORT_ADDR_1);
return (a1 << 8) | a0;
}
static void
rf230_set_short_addr(uint16_t addr)
{
hal_register_write(RG_SHORT_ADDR_0, (addr & 0xFF));
hal_register_write(RG_SHORT_ADDR_1, (addr >> 8));
}
#define RSSI_BASE_VAL (-90)
/* Returns the current CCA threshold in dBm */
static radio_value_t
rf230_get_cca_threshold()
{
radio_value_t cca_thresh = 0;
cca_thresh = hal_subregister_read(SR_CCA_ED_THRES);
cca_thresh = RSSI_BASE_VAL + 2 * cca_thresh;
return cca_thresh;
}
/* Sets the CCA threshold in dBm */
static radio_value_t
rf230_set_cca_threshold(radio_value_t cca_thresh)
{
if(cca_thresh > -60) /* RSSI_BASE_VAL - 2 * 0xF */
cca_thresh = -60;
cca_thresh = (RSSI_BASE_VAL - cca_thresh)/2;
if(cca_thresh < 0)
cca_thresh = - cca_thresh;
hal_subregister_write(SR_CCA_ED_THRES, cca_thresh);
return cca_thresh;
}
/*---------------------------------------------------------------------------*/
static radio_result_t
get_value(radio_param_t param, radio_value_t *value)
{
if(!value) {
return RADIO_RESULT_INVALID_VALUE;
}
switch(param) {
case RADIO_PARAM_POWER_MODE:
*value = rf230_is_sleeping() ? RADIO_POWER_MODE_OFF : RADIO_POWER_MODE_ON;
return RADIO_RESULT_OK;
case RADIO_PARAM_TX_MODE:
return RADIO_RESULT_OK;
case RADIO_PARAM_CHANNEL:
*value = (radio_value_t)rf230_get_channel();
return RADIO_RESULT_OK;
case RADIO_PARAM_PAN_ID:
*value = rf230_get_panid();
return RADIO_RESULT_OK;
case RADIO_PARAM_16BIT_ADDR:
*value = rf230_get_short_addr();
return RADIO_RESULT_OK;
case RADIO_PARAM_RX_MODE:
*value = 0;
if(get_frame_filtering()) {
*value |= RADIO_RX_MODE_ADDRESS_FILTER;
}
if(get_auto_ack()) {
*value |= RADIO_RX_MODE_AUTOACK;
}
if(get_poll_mode()) {
*value |= RADIO_RX_MODE_POLL_MODE;
}
return RADIO_RESULT_OK;
case RADIO_PARAM_TXPOWER:
*value = rf230_get_txpower();
return RADIO_RESULT_OK;
case RADIO_PARAM_CCA_THRESHOLD:
*value = rf230_get_cca_threshold();
return RADIO_RESULT_OK;
case RADIO_PARAM_RSSI:
*value = rf230_get_raw_rssi();
return RADIO_RESULT_OK;
case RADIO_CONST_CHANNEL_MIN:
*value = RF230_MIN_CHANNEL;
return RADIO_RESULT_OK;
case RADIO_CONST_CHANNEL_MAX:
*value = RF230_MAX_CHANNEL;;
return RADIO_RESULT_OK;
case RADIO_CONST_TXPOWER_MIN:
*value = TX_PWR_MIN;
return RADIO_RESULT_OK;
case RADIO_CONST_TXPOWER_MAX:
*value = TX_PWR_MAX;
return RADIO_RESULT_OK;
default:
return RADIO_RESULT_NOT_SUPPORTED;
}
}
/*---------------------------------------------------------------------------*/
static radio_result_t
set_value(radio_param_t param, radio_value_t value)
{
switch(param) {
case RADIO_PARAM_POWER_MODE:
if(value == RADIO_POWER_MODE_ON) {
rf230_on();
return RADIO_RESULT_OK;
}
if(value == RADIO_POWER_MODE_OFF) {
rf230_off();
return RADIO_RESULT_OK;
}
return RADIO_RESULT_INVALID_VALUE;
case RADIO_PARAM_CHANNEL:
if(value < RF230_MIN_CHANNEL ||
value > RF230_MAX_CHANNEL) {
return RADIO_RESULT_INVALID_VALUE;
}
rf230_set_channel(value);
return RADIO_RESULT_OK;
case RADIO_PARAM_TX_MODE:
return RADIO_RESULT_OK;
case RADIO_PARAM_PAN_ID:
rf230_set_panid(value & 0xffff);
return RADIO_RESULT_OK;
case RADIO_PARAM_16BIT_ADDR:
rf230_set_short_addr(value & 0xffff);
return RADIO_RESULT_OK;
case RADIO_PARAM_RX_MODE:
if(value & ~(RADIO_RX_MODE_ADDRESS_FILTER | RADIO_RX_MODE_POLL_MODE |
RADIO_RX_MODE_AUTOACK)) {
return RADIO_RESULT_INVALID_VALUE;
}
set_frame_filtering((value & RADIO_RX_MODE_ADDRESS_FILTER) != 0);
set_auto_ack((value & RADIO_RX_MODE_AUTOACK) != 0);
set_poll_mode((value & RADIO_RX_MODE_POLL_MODE) != 0);
return RADIO_RESULT_OK;
case RADIO_PARAM_TXPOWER:
/* MIN = 15, MAX = 0 */
if(value > TX_PWR_MIN || value < TX_PWR_MAX) {
return RADIO_RESULT_INVALID_VALUE;
}
rf230_set_txpower(value);
return RADIO_RESULT_OK;
case RADIO_PARAM_CCA_THRESHOLD:
rf230_set_cca_threshold(value);
return RADIO_RESULT_OK;
default:
return RADIO_RESULT_NOT_SUPPORTED;
}
}
/*---------------------------------------------------------------------------*/
static radio_result_t
get_object(radio_param_t param, void *dest, size_t size)
{
if(param == RADIO_PARAM_LAST_PACKET_TIMESTAMP) {
if(size != sizeof(rtimer_clock_t) || !dest) {
return RADIO_RESULT_INVALID_VALUE;
}
*(rtimer_clock_t *)dest = rf230_last_rx_packet_timestamp;
return RADIO_RESULT_OK;
}
return RADIO_RESULT_NOT_SUPPORTED;
}
/*---------------------------------------------------------------------------*/
@ -347,7 +598,7 @@ hal_rx_frame_t rxframe[RF230_CONF_RX_BUFFERS];
* \retval STATE_TRANSITION The radio transceiver's state machine is in
* transition between two states.
*/
//static uint8_t
uint8_t
radio_get_trx_state(void)
{
@ -361,8 +612,7 @@ radio_get_trx_state(void)
* states.
* \retval false The radio transceiver is not sleeping.
*/
#if 0
static bool radio_is_sleeping(void)
static bool rf230_is_sleeping(void)
{
bool sleeping = false;
@ -374,7 +624,6 @@ static bool radio_is_sleeping(void)
return sleeping;
}
#endif
/*----------------------------------------------------------------------------*/
/** \brief This function will reset the state machine (to TRX_OFF) from any of
* its states, except for the SLEEP state.
@ -878,7 +1127,7 @@ void rf230_warm_reset(void) {
DDRB &= ~(1<<7);
#endif
hal_register_write(RG_IRQ_MASK, RF230_SUPPORTED_INTERRUPT_MASK);
hal_subregister_write(SR_IRQ_MASK, RF230_SUPPORTED_INTERRUPT_MASK);
/* Set up number of automatic retries 0-15
* (0 implies PLL_ON sends instead of the extended TX_ARET mode */
@ -1310,24 +1559,16 @@ rf230_listen_channel(uint8_t c)
radio_set_trx_state(RX_ON);
}
/*---------------------------------------------------------------------------*/
void
rf230_set_pan_addr(unsigned pan,
unsigned addr,
const uint8_t ieee_addr[8])
//rf230_set_pan_addr(uint16_t pan,uint16_t addr,uint8_t *ieee_addr)
{
PRINTF("rf230: PAN=%x Short Addr=%x\n",pan,addr);
uint8_t abyte;
abyte = pan & 0xFF;
hal_register_write(RG_PAN_ID_0,abyte);
abyte = (pan >> 8*1) & 0xFF;
hal_register_write(RG_PAN_ID_1, abyte);
abyte = addr & 0xFF;
hal_register_write(RG_SHORT_ADDR_0, abyte);
abyte = (addr >> 8*1) & 0xFF;
hal_register_write(RG_SHORT_ADDR_1, abyte);
rf230_set_panid(pan);
rf230_set_short_addr(addr);
if (ieee_addr != NULL) {
PRINTF("MAC=%x",*ieee_addr);
@ -1349,6 +1590,14 @@ rf230_set_pan_addr(unsigned pan,
PRINTF("\n");
}
}
/* From ISR context */
void
rf230_get_last_rx_packet_timestamp(void)
{
rf230_last_rx_packet_timestamp = RTIMER_NOW();
}
/*---------------------------------------------------------------------------*/
/*
* Interrupt leaves frame intact in FIFO.
@ -1872,4 +2121,183 @@ void rf230_start_sneeze(void) {
// while (hal_register_read(0x0f)!=1) {continue;} //wait for pll lock-hangs
hal_register_write(0x02,0x02); //Set TRX_STATE to TX_START
}
#endif
#ifdef AES_128_HW_CONF
#define IEEE_VECT 0
extern unsigned char aes_key[16];
extern unsigned char aes_p[];
extern unsigned char aes_c[];
extern unsigned char aes_s[];
extern unsigned char tmp[16];
/*
After PWR_SAVE sleep key is lost. We'll lock en/decyption to avoid
not to forced in to sleep while doing crypto. Also the key is hold
be the user so AES block should be reentrant. Encode/Docode och 128bit
(16 bytes) is promised to be less than 24us.
Note! Radio must be on to use the HW crypto engine. --ro
*/
static void
rf230_aes_write_key(unsigned char *key)
{
uint8_t i;
for(i = 0; i < 16; i++) {
hal_subregister_write(SR_AES_KEY, key[i]);
}
}
static void
rf230_aes_read_key(unsigned char *key)
{
uint8_t i;
for(i = 0; i < 16; i++) {
key[i] = hal_subregister_read(SR_AES_KEY);
}
}
static void
rf230_aes_write_state(unsigned char *state)
{
uint8_t i;
for(i = 0; i < 16; i++) {
hal_subregister_write(SR_AES_STATE, state[i]);
}
}
static void
rf230_aes_read_state(unsigned char *state)
{
uint8_t i;
for(i = 0; i < 16; i++) {
state[i] = hal_subregister_read(SR_AES_STATE);
}
}
static int
crypt(void)
{
uint8_t status;
hal_subregister_write(SR_AES_CNTRL_REQUEST, 1); /* Kick */
do {
watchdog_periodic();
status = hal_subregister_read(SR_AES_STATUS);
} while(status == 0);
if (hal_subregister_read(SR_AES_STATUS_ERR)) {
PRINTF("AES ERR\n");
return 0;
}
if (hal_subregister_read(SR_AES_STATUS_DONE)) {
PRINTF("AES DONE\n");
return 1;
}
return 0; /* Unknown */
}
int
rf230_aes_encrypt_cbc(unsigned char *key, unsigned char *plain, int len, unsigned char *mic)
{
uint8_t i;
uint8_t sreg;
int res;
sreg = SREG;
cli();
rf230_aes_write_key(key);
hal_subregister_write(SR_AES_CNTRL_MODE, 0); /* AES_MODE=0 -> ECB for 1:st block*/
hal_subregister_write(SR_AES_CNTRL_DIR, 0); /* AES_DIR=0 -> encryption */
/* write string to encrypt into buffer */
for(i = 0; i < 16; i++) {
AES_STATE = plain[i] ^ IEEE_VECT;
}
res = crypt();
if(!res)
goto out;
len -= 16;
/* Swiitch Mode */
hal_subregister_write(SR_AES_CNTRL_MODE, 1); /* AES_MODE=1 -> CBC */
hal_subregister_write(SR_AES_CNTRL_DIR, 0); /* AES_DIR=0 -> encryption */
while(len > 0) {
rf230_aes_write_state(plain);
res = crypt();
if(!res)
goto out;
len -= 16;
}
/* Read and retrun cipher */
rf230_aes_read_state(mic);
out:
SREG = sreg;
return res;
}
/* Electonic Code Block */
int
rf230_aes_encrypt_ebc(unsigned char *key, unsigned char *plain, unsigned char *cipher)
{
int res;
uint8_t sreg;
sreg = SREG;
cli();
rf230_aes_write_key(key);
hal_subregister_write(SR_AES_CNTRL_MODE, 0); /* AES_MODE=0 -> ECB for 1:st block*/
hal_subregister_write(SR_AES_CNTRL_DIR, 0); /* AES_DIR=0 -> encryption */
rf230_aes_write_state(plain); /* write string to encrypt into buffer */
res = crypt();
if(!res)
goto out;
rf230_aes_read_state(cipher); /* Read and return cipher */
out:
SREG = sreg;
return res;
}
int
rf230_aes_decrypt_ebc(unsigned char *key, unsigned char *cipher, unsigned char *plain)
{
int res;
uint8_t sreg;
/*
Dummy encryption of 0 w. original key
to get last round key to be used decrytion
*/
sreg = SREG;
cli();
rf230_aes_write_key(key);
hal_subregister_write(SR_AES_CNTRL_MODE, 0); /* AES_MODE=0 -> ECB for 1:st block*/
hal_subregister_write(SR_AES_CNTRL_DIR, 0); /* AES_DIR=0 -> encryption */
memset(tmp, 0, sizeof(tmp)); /* Setup for last round */
rf230_aes_write_state(tmp);
res = crypt();
if(!res)
goto out;
rf230_aes_read_key(tmp);/* Save the last round key */
/* And use as decrytion key */
rf230_aes_write_key(tmp);
hal_subregister_write(SR_AES_CNTRL_MODE, 0); /* AES_MODE=0 -> ECB for 1:st block*/
hal_subregister_write(SR_AES_CNTRL_DIR, 1); /* AES_DIR=1 -> decryption */
/* Write string to decrypt into buffer */
rf230_aes_write_state(cipher);
res = crypt();
if(!res)
goto out;
rf230_aes_read_state(plain); /* Read plaintext into string */
out:
SREG = sreg;
return res;
}
#endif /* AES_128_HW_CONF */

View file

@ -215,6 +215,7 @@ void rf230_set_channel(uint8_t channel);
void rf230_listen_channel(uint8_t channel);
uint8_t rf230_get_channel(void);
void rf230_set_pan_addr(unsigned pan,unsigned addr,const uint8_t ieee_addr[8]);
unsigned rf230_get_panid(void);
void rf230_set_txpower(uint8_t power);
uint8_t rf230_get_txpower(void);
void rf230_set_rpc(uint8_t rpc);
@ -222,10 +223,14 @@ uint8_t rf230_get_rpc(void);
void rf230_set_promiscuous_mode(bool isPromiscuous);
bool rf230_is_ready_to_send();
static bool rf230_is_sleeping(void);
extern uint8_t rf230_last_correlation,rf230_last_rssi,rf230_smallest_rssi;
uint8_t rf230_get_raw_rssi(void);
int rf230_aes_encrypt_ebc(unsigned char *key, unsigned char *plain, unsigned char *cipher);
int rf230_aes_decrypt_ebc(unsigned char *key, unsigned char *cipher, unsigned char *plain);
int rf230_aes_decrypt_ebc(unsigned char *key, unsigned char *cipher, unsigned char *plain);
#define rf230_rssi rf230_get_raw_rssi

View file

@ -1,6 +1,6 @@
TI_XXWARE_PATH = lib/cc13xxware
CONTIKI_CPU_SOURCEFILES += smartrf-settings.c prop-mode.c
CONTIKI_CPU_SOURCEFILES += smartrf-settings.c prop-mode.c prop-mode-tx-power.c
CFLAGS += -DCPU_FAMILY_CC13XX=1

View file

@ -107,7 +107,7 @@ static int
value(int type)
{
if(type == ADC_SENSOR_VALUE) {
int val;
int val, adj_val, adj_mv;
if(!is_active) {
puts("ADC not active");
@ -119,10 +119,14 @@ value(int type)
ti_lib_aux_adc_gen_manual_trigger();
val = ti_lib_aux_adc_read_fifo();
adj_val = ti_lib_aux_adc_adjust_value_for_gain_and_offset(
val,
ti_lib_aux_adc_get_adjustment_gain(AUXADC_REF_FIXED),
ti_lib_aux_adc_get_adjustment_offset(AUXADC_REF_FIXED));
adj_mv = ti_lib_aux_adc_value_to_microvolts(AUXADC_FIXED_REF_VOLTAGE_NORMAL, adj_val);
ti_lib_aux_adc_disable();
return val;
return adj_mv;
}
return 0;

View file

@ -65,10 +65,20 @@
static int (*input_handler)(unsigned char c);
/*---------------------------------------------------------------------------*/
static bool
usable(void)
usable_rx(void)
{
if(BOARD_IOID_UART_RX == IOID_UNUSED ||
BOARD_IOID_UART_TX == IOID_UNUSED ||
CC26XX_UART_CONF_ENABLE == 0) {
return false;
}
return true;
}
/*---------------------------------------------------------------------------*/
static bool
usable_tx(void)
{
if(BOARD_IOID_UART_TX == IOID_UNUSED ||
CC26XX_UART_CONF_ENABLE == 0) {
return false;
}
@ -271,7 +281,7 @@ cc26xx_uart_init()
bool interrupts_disabled;
/* Return early if disabled by user conf or if ports are misconfigured */
if(usable() == false) {
if(!usable_rx() && !usable_tx()) {
return;
}
@ -299,7 +309,7 @@ void
cc26xx_uart_write_byte(uint8_t c)
{
/* Return early if disabled by user conf or if ports are misconfigured */
if(usable() == false) {
if(usable_tx() == false) {
return;
}
@ -316,7 +326,7 @@ cc26xx_uart_set_input(int (*input)(unsigned char c))
input_handler = input;
/* Return early if disabled by user conf or if ports are misconfigured */
if(usable() == false) {
if(usable_rx() == false) {
return;
}
@ -348,7 +358,7 @@ uint8_t
cc26xx_uart_busy(void)
{
/* Return early if disabled by user conf or if ports are misconfigured */
if(usable() == false) {
if(usable_tx() == false) {
return UART_IDLE;
}

File diff suppressed because it is too large Load diff

View file

@ -1,69 +0,0 @@
/******************************************************************************
* Filename: ble_mailbox.h
* Revised: $ $
* Revision: $ $
*
* Description: Definitions for BLE interface
*
* Copyright (C) 2015 Texas Instruments Incorporated - http://www.ti.com/
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of Texas Instruments Incorporated nor the names of
* its contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
* A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef BLE_MAILBOX_H_
#define BLE_MAILBOX_H_
/// \name Radio operation status
///@{
/// \name Operation finished normally
///@{
#define BLE_DONE_OK 0x1400 ///< Operation ended normally
#define BLE_DONE_RXTIMEOUT 0x1401 ///< Timeout of first Rx of slave operation or end of scan window
#define BLE_DONE_NOSYNC 0x1402 ///< Timeout of subsequent Rx
#define BLE_DONE_RXERR 0x1403 ///< Operation ended because of receive error (CRC or other)
#define BLE_DONE_CONNECT 0x1404 ///< CONNECT_REQ received or transmitted
#define BLE_DONE_MAXNACK 0x1405 ///< Maximum number of retransmissions exceeded
#define BLE_DONE_ENDED 0x1406 ///< Operation stopped after end trigger
#define BLE_DONE_ABORT 0x1407 ///< Operation aborted by command
#define BLE_DONE_STOPPED 0x1408 ///< Operation stopped after stop command
///@}
/// \name Operation finished with error
///@{
#define BLE_ERROR_PAR 0x1800 ///< Illegal parameter
#define BLE_ERROR_RXBUF 0x1801 ///< No available Rx buffer (Advertiser, Scanner, Initiator)
#define BLE_ERROR_NO_SETUP 0x1802 ///< Operation using Rx or Tx attemted when not in BLE mode
#define BLE_ERROR_NO_FS 0x1803 ///< Operation using Rx or Tx attemted without frequency synth configured
#define BLE_ERROR_SYNTH_PROG 0x1804 ///< Synthesizer programming failed to complete on time
#define BLE_ERROR_RXOVF 0x1805 ///< Receiver overflowed during operation
#define BLE_ERROR_TXUNF 0x1806 ///< Transmitter underflowed during operation
///@}
///@}
#endif /* BLE_MAILBOX_H_ */

File diff suppressed because it is too large Load diff

View file

@ -1,213 +0,0 @@
/******************************************************************************
* Filename: data_entry.h
* Revised: 2015-08-04 11:44:20 +0200 (Tue, 04 Aug 2015)
* Revision: 44329
*
* Description: Definition of API for data exchange
*
* Copyright (c) 2015, Texas Instruments Incorporated
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1) Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
*
* 2) Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* 3) Neither the name of the ORGANIZATION nor the names of its contributors may
* be used to endorse or promote products derived from this software without
* specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef DATA_ENTRY_H_
#define DATA_ENTRY_H_
#ifndef __RFC_STRUCT
#ifdef __GNUC__
#define __RFC_STRUCT __attribute__ ((aligned (4)))
#else
#define __RFC_STRUCT
#endif
#endif
//! \addtogroup rfc
//! @{
//! \addtogroup data_entry
//! @{
#include <stdint.h>
#include "mailbox.h"
typedef struct __RFC_STRUCT rfc_dataEntry_s rfc_dataEntry_t;
typedef struct __RFC_STRUCT rfc_dataEntryGeneral_s rfc_dataEntryGeneral_t;
typedef struct __RFC_STRUCT rfc_dataEntryMulti_s rfc_dataEntryMulti_t;
typedef struct __RFC_STRUCT rfc_dataEntryPointer_s rfc_dataEntryPointer_t;
typedef struct __RFC_STRUCT rfc_dataEntryPartial_s rfc_dataEntryPartial_t;
//! \addtogroup dataEntry
//! @{
struct __RFC_STRUCT rfc_dataEntry_s {
uint8_t* pNextEntry; //!< Pointer to next entry in the queue, NULL if this is the last entry
uint8_t status; //!< Indicates status of entry, including whether it is free for the system CPU to write to
struct {
uint8_t type:2; //!< \brief Type of data entry structure<br>
//!< 0: General data entry <br>
//!< 1: Multi-element Rx entry<br>
//!< 2: Pointer entry<br>
//!< 3: Partial read Rx entry
uint8_t lenSz:2; //!< \brief Size of length word in start of each Rx entry element<br>
//!< 0: No length indicator<br>
//!< 1: One byte length indicator<br>
//!< 2: Two bytes length indicator<br>
//!< 3: <i>Reserved</i>
uint8_t irqIntv:4; //!< \brief For partial read Rx entry only: The number of bytes between interrupt generated
//!< by the radio CPU (0: 16 bytes)
} config;
uint16_t length; //!< \brief For pointer entries: Number of bytes in the data buffer pointed to<br>
//!< For other entries: Number of bytes following this length field
};
//! @}
//! \addtogroup dataEntryGeneral
//! @{
//! General data entry structure (type = 0)
struct __RFC_STRUCT rfc_dataEntryGeneral_s {
uint8_t* pNextEntry; //!< Pointer to next entry in the queue, NULL if this is the last entry
uint8_t status; //!< Indicates status of entry, including whether it is free for the system CPU to write to
struct {
uint8_t type:2; //!< \brief Type of data entry structure<br>
//!< 0: General data entry <br>
//!< 1: Multi-element Rx entry<br>
//!< 2: Pointer entry<br>
//!< 3: Partial read Rx entry
uint8_t lenSz:2; //!< \brief Size of length word in start of each Rx entry element<br>
//!< 0: No length indicator<br>
//!< 1: One byte length indicator<br>
//!< 2: Two bytes length indicator<br>
//!< 3: <i>Reserved</i>
uint8_t irqIntv:4; //!< \brief For partial read Rx entry only: The number of bytes between interrupt generated
//!< by the radio CPU (0: 16 bytes)
} config;
uint16_t length; //!< \brief For pointer entries: Number of bytes in the data buffer pointed to<br>
//!< For other entries: Number of bytes following this length field
uint8_t data; //!< First byte of the data array to be received or transmitted
};
//! @}
//! \addtogroup dataEntryMulti
//! @{
//! Multi-element data entry structure (type = 1)
struct __RFC_STRUCT rfc_dataEntryMulti_s {
uint8_t* pNextEntry; //!< Pointer to next entry in the queue, NULL if this is the last entry
uint8_t status; //!< Indicates status of entry, including whether it is free for the system CPU to write to
struct {
uint8_t type:2; //!< \brief Type of data entry structure<br>
//!< 0: General data entry <br>
//!< 1: Multi-element Rx entry<br>
//!< 2: Pointer entry<br>
//!< 3: Partial read Rx entry
uint8_t lenSz:2; //!< \brief Size of length word in start of each Rx entry element<br>
//!< 0: No length indicator<br>
//!< 1: One byte length indicator<br>
//!< 2: Two bytes length indicator<br>
//!< 3: <i>Reserved</i>
uint8_t irqIntv:4; //!< \brief For partial read Rx entry only: The number of bytes between interrupt generated
//!< by the radio CPU (0: 16 bytes)
} config;
uint16_t length; //!< \brief For pointer entries: Number of bytes in the data buffer pointed to<br>
//!< For other entries: Number of bytes following this length field
uint16_t numElements; //!< Number of entry elements committed in the entry
uint16_t nextIndex; //!< Index to the byte after the last byte of the last entry element committed by the radio CPU
uint8_t rxData; //!< First byte of the data array of received data entry elements
};
//! @}
//! \addtogroup dataEntryPointer
//! @{
//! Pointer data entry structure (type = 2)
struct __RFC_STRUCT rfc_dataEntryPointer_s {
uint8_t* pNextEntry; //!< Pointer to next entry in the queue, NULL if this is the last entry
uint8_t status; //!< Indicates status of entry, including whether it is free for the system CPU to write to
struct {
uint8_t type:2; //!< \brief Type of data entry structure<br>
//!< 0: General data entry <br>
//!< 1: Multi-element Rx entry<br>
//!< 2: Pointer entry<br>
//!< 3: Partial read Rx entry
uint8_t lenSz:2; //!< \brief Size of length word in start of each Rx entry element<br>
//!< 0: No length indicator<br>
//!< 1: One byte length indicator<br>
//!< 2: Two bytes length indicator<br>
//!< 3: <i>Reserved</i>
uint8_t irqIntv:4; //!< \brief For partial read Rx entry only: The number of bytes between interrupt generated
//!< by the radio CPU (0: 16 bytes)
} config;
uint16_t length; //!< \brief For pointer entries: Number of bytes in the data buffer pointed to<br>
//!< For other entries: Number of bytes following this length field
uint8_t* pData; //!< Pointer to data buffer of data to be received ro transmitted
};
//! @}
//! \addtogroup dataEntryPartial
//! @{
//! Partial read data entry structure (type = 3)
struct __RFC_STRUCT rfc_dataEntryPartial_s {
uint8_t* pNextEntry; //!< Pointer to next entry in the queue, NULL if this is the last entry
uint8_t status; //!< Indicates status of entry, including whether it is free for the system CPU to write to
struct {
uint8_t type:2; //!< \brief Type of data entry structure<br>
//!< 0: General data entry <br>
//!< 1: Multi-element Rx entry<br>
//!< 2: Pointer entry<br>
//!< 3: Partial read Rx entry
uint8_t lenSz:2; //!< \brief Size of length word in start of each Rx entry element<br>
//!< 0: No length indicator<br>
//!< 1: One byte length indicator<br>
//!< 2: Two bytes length indicator<br>
//!< 3: <i>Reserved</i>
uint8_t irqIntv:4; //!< \brief For partial read Rx entry only: The number of bytes between interrupt generated
//!< by the radio CPU (0: 16 bytes)
} config;
uint16_t length; //!< \brief For pointer entries: Number of bytes in the data buffer pointed to<br>
//!< For other entries: Number of bytes following this length field
struct {
uint16_t numElements:13; //!< Number of entry elements committed in the entry
uint16_t bEntryOpen:1; //!< 1 if the entry contains an element that is still open for appending data
uint16_t bFirstCont:1; //!< 1 if the first element is a continuation of the last packet from the previous entry
uint16_t bLastCont:1; //!< 1 if the packet in the last element continues in the next entry
} pktStatus;
uint16_t nextIndex; //!< Index to the byte after the last byte of the last entry element committed by the radio CPU
uint8_t rxData; //!< First byte of the data array of received data entry elements
};
//! @}
//! @}
//! @}
#endif /* DATA_ENTRY_H_ */

View file

@ -55,8 +55,8 @@
//! @{
#include <stdint.h>
#include "mailbox.h"
#include "common_cmd.h"
#include "driverlib/rf_mailbox.h"
#include "driverlib/rf_common_cmd.h"
typedef struct __RFC_STRUCT rfc_CMD_IEEE_RX_s rfc_CMD_IEEE_RX_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_ED_SCAN_s rfc_CMD_IEEE_ED_SCAN_t;

View file

@ -40,7 +40,7 @@
#ifndef IEEE_MAILBOX_H_
#define IEEE_MAILBOX_H_
#include "mailbox.h"
#include "driverlib/rf_mailbox.h"
/// \name Radio operation status

View file

@ -1,328 +0,0 @@
/******************************************************************************
* Filename: mailbox.h
* Revised: 2015-06-29 12:59:58 +0200 (Mon, 29 Jun 2015)
* Revision: 44063
*
* Description: Definitions for interface between system and radio CPU
*
* Copyright (c) 2015, Texas Instruments Incorporated
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1) Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
*
* 2) Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* 3) Neither the name of the ORGANIZATION nor the names of its contributors may
* be used to endorse or promote products derived from this software without
* specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef MAILBOX_H_
#define MAILBOX_H_
#include <stdint.h>
#include <string.h>
/// Type definition for RAT
typedef uint32_t ratmr_t;
/// Type definition for a data queue
typedef struct {
uint8_t *pCurrEntry; ///< Pointer to the data queue entry to be used, NULL for an empty queue
uint8_t *pLastEntry; ///< Pointer to the last entry in the queue, NULL for a circular queue
} dataQueue_t;
/// \name CPE interrupt definitions
/// Interrupt masks for the CPE interrupt in RDBELL.
///@{
#define IRQN_COMMAND_DONE 0 ///< Radio operation command finished
#define IRQN_LAST_COMMAND_DONE 1 ///< Last radio operation command in a chain finished
#define IRQN_FG_COMMAND_DONE 2 ///< FG level Radio operation command finished
#define IRQN_LAST_FG_COMMAND_DONE 3 ///< Last FG level radio operation command in a chain finished
#define IRQN_TX_DONE 4 ///< Packet transmitted
#define IRQN_TX_ACK 5 ///< ACK packet transmitted
#define IRQN_TX_CTRL 6 ///< Control packet transmitted
#define IRQN_TX_CTRL_ACK 7 ///< Acknowledgement received on a transmitted control packet
#define IRQN_TX_CTRL_ACK_ACK 8 ///< Acknowledgement received on a transmitted control packet, and acknowledgement transmitted for that packet
#define IRQN_TX_RETRANS 9 ///< Packet retransmitted
#define IRQN_TX_ENTRY_DONE 10 ///< Tx queue data entry state changed to Finished
#define IRQN_TX_BUFFER_CHANGED 11 ///< A buffer change is complete
#define IRQN_RX_OK 16 ///< Packet received with CRC OK, payload, and not to be ignored
#define IRQN_RX_NOK 17 ///< Packet received with CRC error
#define IRQN_RX_IGNORED 18 ///< Packet received with CRC OK, but to be ignored
#define IRQN_RX_EMPTY 19 ///< Packet received with CRC OK, not to be ignored, no payload
#define IRQN_RX_CTRL 20 ///< Control packet received with CRC OK, not to be ignored
#define IRQN_RX_CTRL_ACK 21 ///< Control packet received with CRC OK, not to be ignored, then ACK sent
#define IRQN_RX_BUF_FULL 22 ///< Packet received that did not fit in the Rx queue
#define IRQN_RX_ENTRY_DONE 23 ///< Rx queue data entry changing state to Finished
#define IRQN_RX_DATA_WRITTEN 24 ///< Data written to partial read Rx buffer
#define IRQN_RX_N_DATA_WRITTEN 25 ///< Specified number of bytes written to partial read Rx buffer
#define IRQN_RX_ABORTED 26 ///< Packet reception stopped before packet was done
#define IRQN_RX_COLLISION_DETECTED 27 ///< A collision was indicated during packet reception
#define IRQN_SYNTH_NO_LOCK 28 ///< The synth has gone out of lock after calibration
#define IRQN_MODULES_UNLOCKED 29 ///< As part of the boot process, the CM0 has opened access to RF core modules and memories
#define IRQN_BOOT_DONE 30 ///< The RF core CPU boot is finished
#define IRQN_INTERNAL_ERROR 31 ///< Internal error observed
#define IRQ_COMMAND_DONE (1U << IRQN_COMMAND_DONE)
#define IRQ_LAST_COMMAND_DONE (1U << IRQN_LAST_COMMAND_DONE)
#define IRQ_FG_COMMAND_DONE (1U << IRQN_FG_COMMAND_DONE)
#define IRQ_LAST_FG_COMMAND_DONE (1U << IRQN_LAST_FG_COMMAND_DONE)
#define IRQ_TX_DONE (1U << IRQN_TX_DONE)
#define IRQ_TX_ACK (1U << IRQN_TX_ACK)
#define IRQ_TX_CTRL (1U << IRQN_TX_CTRL)
#define IRQ_TX_CTRL_ACK (1U << IRQN_TX_CTRL_ACK)
#define IRQ_TX_CTRL_ACK_ACK (1U << IRQN_TX_CTRL_ACK_ACK)
#define IRQ_TX_RETRANS (1U << IRQN_TX_RETRANS)
#define IRQ_TX_ENTRY_DONE (1U << IRQN_TX_ENTRY_DONE)
#define IRQ_TX_BUFFER_CHANGED (1U << IRQN_TX_BUFFER_CHANGED)
#define IRQ_RX_OK (1U << IRQN_RX_OK)
#define IRQ_RX_NOK (1U << IRQN_RX_NOK)
#define IRQ_RX_IGNORED (1U << IRQN_RX_IGNORED)
#define IRQ_RX_EMPTY (1U << IRQN_RX_EMPTY)
#define IRQ_RX_CTRL (1U << IRQN_RX_CTRL)
#define IRQ_RX_CTRL_ACK (1U << IRQN_RX_CTRL_ACK)
#define IRQ_RX_BUF_FULL (1U << IRQN_RX_BUF_FULL)
#define IRQ_RX_ENTRY_DONE (1U << IRQN_RX_ENTRY_DONE)
#define IRQ_RX_DATA_WRITTEN (1U << IRQN_RX_DATA_WRITTEN)
#define IRQ_RX_N_DATA_WRITTEN (1U << IRQN_RX_N_DATA_WRITTEN)
#define IRQ_RX_ABORTED (1U << IRQN_RX_ABORTED)
#define IRQ_RX_COLLISION_DETECTED (1U << IRQN_RX_COLLISION_DETECTED)
#define IRQ_SYNTH_NO_LOCK (1U << IRQN_SYNTH_NO_LOCK)
#define IRQ_MODULES_UNLOCKED (1U << IRQN_MODULES_UNLOCKED)
#define IRQ_BOOT_DONE (1U << IRQN_BOOT_DONE)
#define IRQ_INTERNAL_ERROR (1U << IRQN_INTERNAL_ERROR)
///@}
/// \name CMDSTA values
/// Values returned in result byte of CMDSTA
///@{
#define CMDSTA_Pending 0x00 ///< The command has not yet been parsed
#define CMDSTA_Done 0x01 ///< Command successfully parsed
#define CMDSTA_IllegalPointer 0x81 ///< The pointer signalled in CMDR is not valid
#define CMDSTA_UnknownCommand 0x82 ///< The command number in the command structure is unknown
#define CMDSTA_UnknownDirCommand 0x83 ///< The command number for a direct command is unknown, or the
///< command is not a direct command
#define CMDSTA_ContextError 0x85 ///< An immediate or direct command was issued in a context
///< where it is not supported
#define CMDSTA_SchedulingError 0x86 ///< A radio operation command was attempted to be scheduled
///< while another operation was already running in the RF core
#define CMDSTA_ParError 0x87 ///< There were errors in the command parameters that are parsed
///< on submission.
#define CMDSTA_QueueError 0x88 ///< An operation on a data entry queue was attempted that was
///< not supported by the queue in its current state
#define CMDSTA_QueueBusy 0x89 ///< An operation on a data entry was attempted while that entry
///< was busy
///@}
/// \name Macros for sending direct commands
///@{
/// Direct command with no parameter
#define CMDR_DIR_CMD(cmdId) (((cmdId) << 16) | 1)
/// Direct command with 1-byte parameter
#define CMDR_DIR_CMD_1BYTE(cmdId, par) (((cmdId) << 16) | ((par) << 8) | 1)
/// Direct command with 2-byte parameter
#define CMDR_DIR_CMD_2BYTE(cmdId, par) (((cmdId) << 16) | ((par) & 0xFFFC) | 1)
///@}
/// \name Definitions for trigger types
///@{
#define TRIG_NOW 0 ///< Triggers immediately
#define TRIG_NEVER 1 ///< Never trigs
#define TRIG_ABSTIME 2 ///< Trigs at an absolute time
#define TRIG_REL_SUBMIT 3 ///< Trigs at a time relative to the command was submitted
#define TRIG_REL_START 4 ///< Trigs at a time relative to the command started
#define TRIG_REL_PREVSTART 5 ///< Trigs at a time relative to the previous command in the chain started
#define TRIG_REL_FIRSTSTART 6 ///< Trigs at a time relative to the first command in the chain started
#define TRIG_REL_PREVEND 7 ///< Trigs at a time relative to the previous command in the chain ended
#define TRIG_REL_EVT1 8 ///< Trigs at a time relative to the context defined "Event 1"
#define TRIG_REL_EVT2 9 ///< Trigs at a time relative to the context defined "Event 2"
#define TRIG_EXTERNAL 10 ///< Trigs at an external event to the radio timer
#define TRIG_PAST_BM 0x80 ///< Bitmask for setting pastTrig bit in order to trig immediately if
///< trigger happened in the past
///@}
/// \name Definitions for conditional execution
///@{
#define COND_ALWAYS 0 ///< Always run next command (except in case of Abort)
#define COND_NEVER 1 ///< Never run next command
#define COND_STOP_ON_FALSE 2 ///< Run next command if this command returned True, stop if it returned
///< False
#define COND_STOP_ON_TRUE 3 ///< Stop if this command returned True, run next command if it returned
///< False
#define COND_SKIP_ON_FALSE 4 ///< Run next command if this command returned True, skip a number of
///< commands if it returned False
#define COND_SKIP_ON_TRUE 5 ///< Skip a number of commands if this command returned True, run next
///< command if it returned False
///@}
/// \name Radio operation status
///@{
/// \name Operation not finished
///@{
#define IDLE 0x0000 ///< Operation not started
#define PENDING 0x0001 ///< Start of command is pending
#define ACTIVE 0x0002 ///< Running
#define SKIPPED 0x0003 ///< Operation skipped due to condition in another command
///@}
/// \name Operation finished normally
///@{
#define DONE_OK 0x0400 ///< Operation ended normally
#define DONE_COUNTDOWN 0x0401 ///< Counter reached zero
#define DONE_RXERR 0x0402 ///< Operation ended with CRC error
#define DONE_TIMEOUT 0x0403 ///< Operation ended with timeout
#define DONE_STOPPED 0x0404 ///< Operation stopped after CMD_STOP command
#define DONE_ABORT 0x0405 ///< Operation aborted by CMD_ABORT command
#define DONE_FAILED 0x0406 ///< Scheduled immediate command failed
///@}
/// \name Operation finished with error
///@{
#define ERROR_PAST_START 0x0800 ///< The start trigger occurred in the past
#define ERROR_START_TRIG 0x0801 ///< Illegal start trigger parameter
#define ERROR_CONDITION 0x0802 ///< Illegal condition for next operation
#define ERROR_PAR 0x0803 ///< Error in a command specific parameter
#define ERROR_POINTER 0x0804 ///< Invalid pointer to next operation
#define ERROR_CMDID 0x0805 ///< Next operation has a command ID that is undefined or not a radio
///< operation command
#define ERROR_WRONG_BG 0x0806 ///< FG level command not compatible with running BG level command
#define ERROR_NO_SETUP 0x0807 ///< Operation using Rx or Tx attempted without CMD_RADIO_SETUP
#define ERROR_NO_FS 0x0808 ///< Operation using Rx or Tx attempted without frequency synth configured
#define ERROR_SYNTH_PROG 0x0809 ///< Synthesizer calibration failed
#define ERROR_TXUNF 0x080A ///< Tx underflow observed
#define ERROR_RXOVF 0x080B ///< Rx overflow observed
#define ERROR_NO_RX 0x080C ///< Attempted to access data from Rx when no such data was yet received
#define ERROR_PENDING 0x080D ///< Command submitted in the future with another command at different level pending
///@}
///@}
/// \name Data entry types
///@{
#define DATA_ENTRY_TYPE_GEN 0 ///< General type: Tx entry or single element Rx entry
#define DATA_ENTRY_TYPE_MULTI 1 ///< Multi-element Rx entry type
#define DATA_ENTRY_TYPE_PTR 2 ///< Pointer entry type
#define DATA_ENTRY_TYPE_PARTIAL 3 ///< Partial read entry type
///@
/// \name Data entry statuses
///@{
#define DATA_ENTRY_PENDING 0 ///< Entry not yet used
#define DATA_ENTRY_ACTIVE 1 ///< Entry in use by radio CPU
#define DATA_ENTRY_BUSY 2 ///< Entry being updated
#define DATA_ENTRY_FINISHED 3 ///< Radio CPU is finished accessing the entry
#define DATA_ENTRY_UNFINISHED 4 ///< Radio CPU is finished accessing the entry, but packet could not be finished
///@}
/// \name Macros for RF register override
///@{
/// Macro for ADI half-size value-mask combination
#define ADI_VAL_MASK(addr, mask, value) \
(((addr) & 1) ? (((mask) & 0x0F) | (((value) & 0x0F) << 4)) : \
((((mask) & 0x0F) << 4) | ((value) & 0x0F)))
/// 32-bit write of 16-bit value
#define HW_REG_OVERRIDE(addr, val) ((((uintptr_t) (addr)) & 0xFFFC) | ((uint32_t)(val) << 16))
/// ADI register, full-size write
#define ADI_REG_OVERRIDE(adiNo, addr, val) (2 | ((uint32_t)(val) << 16) | \
(((addr) & 0x3F) << 24) | (((adiNo) ? 1U : 0) << 31))
/// 2 ADI registers, full-size write
#define ADI_2REG_OVERRIDE(adiNo, addr, val, addr2, val2) \
(2 | ((uint32_t)(val2) << 2) | (((addr2) & 0x3F) << 10) | ((uint32_t)(val) << 16) | \
(((addr) & 0x3F) << 24) | (((adiNo) ? 1U : 0) << 31))
/// ADI register, half-size read-modify-write
#define ADI_HALFREG_OVERRIDE(adiNo, addr, mask, val) (2 | (ADI_VAL_MASK(addr, mask, val) << 16) | \
(((addr) & 0x3F) << 24) | (1U << 30) | (((adiNo) ? 1U : 0) << 31))
/// 2 ADI registers, half-size read-modify-write
#define ADI_2HALFREG_OVERRIDE(adiNo, addr, mask, val, addr2, mask2, val2) \
(2 | (ADI_VAL_MASK(addr2, mask2, val2) << 2) | (((addr2) & 0x3F) << 10) | \
(ADI_VAL_MASK(addr, mask, val) << 16) | (((addr) & 0x3F) << 24) | (1U << 30) | (((adiNo) ? 1U : 0) << 31))
/// 16-bit SW register as defined in radio_par_def.txt
#define SW_REG_OVERRIDE(cmd, field, val) (3 | ((_POSITION_##cmd##_##field) << 4) | ((uint32_t)(val) << 16))
/// SW register as defined in radio_par_def.txt with added index (for use with registers > 16 bits).
#define SW_REG_IND_OVERRIDE(cmd, field, offset, val) (3 | \
(((_POSITION_##cmd##_##field) + ((offset) << 1)) << 4) | ((uint32_t)(val) << 16))
/// 8-bit SW register as defined in radio_par_def.txt
#define SW_REG_BYTE_OVERRIDE(cmd, field, val) (0x8003 | ((_POSITION_##cmd##_##field) << 4) | \
((uint32_t)(val) << 16))
/// Two 8-bit SW registers as defined in radio_par_def.txt; the one given by field and the next byte.
#define SW_REG_2BYTE_OVERRIDE(cmd, field, val0, val1) (3 | (((_POSITION_##cmd##_##field) & 0xFFFE) << 4) | \
(((uint32_t)(val0) << 16) & 0x00FF0000) | ((uint32_t)(val1) << 24))
#define HW16_ARRAY_OVERRIDE(addr, length) (1 | (((uintptr_t) (addr)) & 0xFFFC) | ((uint32_t)(length) << 16))
#define HW32_ARRAY_OVERRIDE(addr, length) (1 | (((uintptr_t) (addr)) & 0xFFFC) | \
((uint32_t)(length) << 16) | (1U << 30))
#define ADI_ARRAY_OVERRIDE(adiNo, addr, bHalfSize, length) (1 | ((((addr) & 0x3F) << 2)) | \
((!!(bHalfSize)) << 8) | ((!!(adiNo)) << 9) | ((uint32_t)(length) << 16) | (2U << 30))
#define SW_ARRAY_OVERRIDE(cmd, firstfield, length) (1 | (((_POSITION_##cmd##_##firstfield)) << 2) | \
((uint32_t)(length) << 16) | (3U << 30))
#define MCE_RFE_OVERRIDE(bMceRam, mceRomBank, mceMode, bRfeRam, rfeRomBank, rfeMode) \
(7 | ((!!(bMceRam)) << 8) | (((mceRomBank) & 0x07) << 9) | ((!!(bRfeRam)) << 12) | (((rfeRomBank) & 0x07) << 13) | \
(((mceMode) & 0x00FF) << 16) | (((rfeMode) & 0x00FF) << 24))
#define NEW_OVERRIDE_SEGMENT(address) (((((uintptr_t)(address)) & 0x03FFFFFC) << 6) | 0x000F | \
(((((uintptr_t)(address) >> 24) == 0x20) ? 0x01 : \
(((uintptr_t)(address) >> 24) == 0x21) ? 0x02 : \
(((uintptr_t)(address) >> 24) == 0xA0) ? 0x03 : \
(((uintptr_t)(address) >> 24) == 0x00) ? 0x04 : \
(((uintptr_t)(address) >> 24) == 0x10) ? 0x05 : \
(((uintptr_t)(address) >> 24) == 0x11) ? 0x06 : \
(((uintptr_t)(address) >> 24) == 0x40) ? 0x07 : \
(((uintptr_t)(address) >> 24) == 0x50) ? 0x08 : \
0x09) << 4)) // Use illegal value for illegal address range
/// End of string for override register
#define END_OVERRIDE 0xFFFFFFFF
/// ADI address-value pair
#define ADI_ADDR_VAL(addr, value) ((((addr) & 0x7F) << 8) | ((value) & 0xFF))
#define ADI_ADDR_VAL_MASK(addr, mask, value) ((((addr) & 0x7F) << 8) | ADI_VAL_MASK(addr, mask, value))
/// Low half-word
#define LOWORD(value) ((value) & 0xFFFF)
/// High half-word
#define HIWORD(value) ((value) >> 16)
///@}
#endif /* MAILBOX_H_ */

View file

@ -1,596 +0,0 @@
/******************************************************************************
* Filename: prop_cmd.h
* Revised: 2015-08-04 10:40:45 +0200 (Tue, 04 Aug 2015)
* Revision: 44326
*
* Description: CC13xx API for Proprietary mode commands
*
* Copyright (c) 2015, Texas Instruments Incorporated
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1) Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
*
* 2) Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* 3) Neither the name of the ORGANIZATION nor the names of its contributors may
* be used to endorse or promote products derived from this software without
* specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef PROP_CMD_H_
#define PROP_CMD_H_
#ifndef __RFC_STRUCT
#ifdef __GNUC__
#define __RFC_STRUCT __attribute__ ((aligned (4)))
#else
#define __RFC_STRUCT
#endif
#endif
//! \addtogroup rfc
//! @{
//! \addtogroup prop_cmd
//! @{
#include <stdint.h>
#include "mailbox.h"
#include "common_cmd.h"
typedef struct __RFC_STRUCT rfc_carrierSense_s rfc_carrierSense_t;
typedef struct __RFC_STRUCT rfc_CMD_PROP_TX_s rfc_CMD_PROP_TX_t;
typedef struct __RFC_STRUCT rfc_CMD_PROP_RX_s rfc_CMD_PROP_RX_t;
typedef struct __RFC_STRUCT rfc_CMD_PROP_TX_ADV_s rfc_CMD_PROP_TX_ADV_t;
typedef struct __RFC_STRUCT rfc_CMD_PROP_RX_ADV_s rfc_CMD_PROP_RX_ADV_t;
typedef struct __RFC_STRUCT rfc_CMD_PROP_RADIO_SETUP_s rfc_CMD_PROP_RADIO_SETUP_t;
typedef struct __RFC_STRUCT rfc_CMD_PROP_RADIO_DIV_SETUP_s rfc_CMD_PROP_RADIO_DIV_SETUP_t;
typedef struct __RFC_STRUCT rfc_CMD_PROP_SET_LEN_s rfc_CMD_PROP_SET_LEN_t;
typedef struct __RFC_STRUCT rfc_CMD_PROP_RESTART_RX_s rfc_CMD_PROP_RESTART_RX_t;
typedef struct __RFC_STRUCT rfc_propRxOutput_s rfc_propRxOutput_t;
typedef struct __RFC_STRUCT rfc_propRxStatus_s rfc_propRxStatus_t;
//! \addtogroup carrierSense
//! @{
struct __RFC_STRUCT rfc_carrierSense_s {
struct {
uint8_t bEnaRssi:1; //!< If 1, enable RSSI as a criterion
uint8_t bEnaCorr:1; //!< If 1, enable correlation as a criterion
uint8_t operation:1; //!< \brief 0: Busy if either RSSI or correlation indicates Busy<br>
//!< 1: Busy if both RSSI and correlation indicates Busy
uint8_t busyOp:1; //!< \brief 0: Continue carrier sense on channel Busy<br>
//!< 1: End carrier sense on channel Busy<br>
//!< For an Rx command, the receiver will continue when carrier sense ends, but it will then not end if channel goes Idle
uint8_t idleOp:1; //!< \brief 0: Continue on channel Idle<br>
//!< 1: End on channel Idle
uint8_t timeoutRes:1; //!< \brief 0: Timeout with channel state Invalid treated as Busy<br>
//!< 1: Timeout with channel state Invalid treated as Idle
} csConf;
int8_t rssiThr; //!< RSSI threshold
uint8_t numRssiIdle; //!< \brief Number of consecutive RSSI measurements below the threshold needed before the channel is
//!< declared Idle
uint8_t numRssiBusy; //!< \brief Number of consecutive RSSI measurements above the threshold needed before the channel is
//!< declared Busy
uint16_t corrPeriod; //!< Number of RAT ticks for a correlation observation periods
struct {
uint8_t numCorrInv:4; //!< \brief Number of subsequent correlation tops with maximum <code>corrPeriod</code> RAT
//!< ticks between them needed to go from Idle to Invalid
uint8_t numCorrBusy:4; //!< \brief Number of subsequent correlation tops with maximum <code>corrPeriod</code> RAT
//!< ticks between them needed to go from Invalid to Busy
} corrConfig;
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} csEndTrigger; //!< Trigger classifier for ending the carrier sense
ratmr_t csEndTime; //!< Time used together with <code>csEndTrigger</code> for ending the operation
};
//! @}
//! \addtogroup CMD_PROP_TX
//! @{
#define CMD_PROP_TX 0x3801
struct __RFC_STRUCT rfc_CMD_PROP_TX_s {
uint16_t commandNo; //!< The command ID number 0x3801
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
struct {
uint8_t bFsOff:1; //!< \brief 0: Keep frequency synth on after command<br>
//!< 1: Turn frequency synth off after command
uint8_t :2;
uint8_t bUseCrc:1; //!< \brief 0: Do not append CRC<br>
//!< 1: Append CRC
uint8_t bVarLen:1; //!< \brief 0: Fixed length<br>
//!< 1: Transmit length as first byte
} pktConf;
uint8_t pktLen; //!< Packet length
uint32_t syncWord; //!< Sync word to transmit
uint8_t* pPkt; //!< Pointer to packet
};
//! @}
//! \addtogroup CMD_PROP_RX
//! @{
#define CMD_PROP_RX 0x3802
struct __RFC_STRUCT rfc_CMD_PROP_RX_s {
uint16_t commandNo; //!< The command ID number 0x3802
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
struct {
uint8_t bFsOff:1; //!< \brief 0: Keep frequency synth on after command<br>
//!< 1: Turn frequency synth off after command
uint8_t bRepeatOk:1; //!< \brief 0: End operation after receiving a packet correctly<br>
//!< 1: Go back to sync search after receiving a packet correctly
uint8_t bRepeatNok:1; //!< \brief 0: End operation after receiving a packet with CRC error<br>
//!< 1: Go back to sync search after receiving a packet with CRC error
uint8_t bUseCrc:1; //!< \brief 0: Do not check CRC<br>
//!< 1: Check CRC
uint8_t bVarLen:1; //!< \brief 0: Fixed length<br>
//!< 1: Receive length as first byte
uint8_t bChkAddress:1; //!< \brief 0: No address check<br>
//!< 1: Check address
uint8_t endType:1; //!< \brief 0: Packet is received to the end if end trigger happens after sync is obtained<br>
//!< 1: Packet reception is stopped if end trigger happens
uint8_t filterOp:1; //!< \brief 0: Stop receiver and restart sync search on address mismatch<br>
//!< 1: Receive packet and mark it as ignored on address mismatch
} pktConf;
struct {
uint8_t bAutoFlushIgnored:1; //!< If 1, automatically discard ignored packets from Rx queue
uint8_t bAutoFlushCrcErr:1; //!< If 1, automatically discard packets with CRC error from Rx queue
uint8_t :1;
uint8_t bIncludeHdr:1; //!< If 1, include the received header or length byte in the stored packet; otherwise discard it
uint8_t bIncludeCrc:1; //!< If 1, include the received CRC field in the stored packet; otherwise discard it
uint8_t bAppendRssi:1; //!< If 1, append an RSSI byte to the packet in the Rx queue
uint8_t bAppendTimestamp:1; //!< If 1, append a timestamp to the packet in the Rx queue
uint8_t bAppendStatus:1; //!< If 1, append a status byte to the packet in the Rx queue
} rxConf; //!< Rx configuration
uint32_t syncWord; //!< Sync word to listen for
uint8_t maxPktLen; //!< \brief Packet length for fixed length, maximum packet length for variable length<br>
//!< 0: Unlimited or unknown length
uint8_t address0; //!< Address
uint8_t address1; //!< \brief Address (set equal to <code>address0</code> to accept only one address. If 0xFF, accept
//!< 0x00 as well)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} endTrigger; //!< Trigger classifier for ending the operation
ratmr_t endTime; //!< Time used together with <code>endTrigger</code> for ending the operation
dataQueue_t* pQueue; //!< Pointer to receive queue
uint8_t* pOutput; //!< Pointer to output structure
};
//! @}
//! \addtogroup CMD_PROP_TX_ADV
//! @{
#define CMD_PROP_TX_ADV 0x3803
struct __RFC_STRUCT rfc_CMD_PROP_TX_ADV_s {
uint16_t commandNo; //!< The command ID number 0x3803
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
struct {
uint8_t bFsOff:1; //!< \brief 0: Keep frequency synth on after command<br>
//!< 1: Turn frequency synth off after command
uint8_t :2;
uint8_t bUseCrc:1; //!< \brief 0: Do not append CRC<br>
//!< 1: Append CRC
uint8_t bCrcIncSw:1; //!< \brief 0:Do not include sync word in CRC calculation<br>
//!< 1: Include sync word in CRC calculation
uint8_t bCrcIncHdr:1; //!< \brief 0: Do not include header in CRC calculation<br>
//!< 1: Include header in CRC calculation
} pktConf;
uint8_t numHdrBits; //!< Number of bits in header (0&ndash;32)
uint16_t pktLen; //!< Packet length. 0: Unlimited
struct {
uint8_t bExtTxTrig:1; //!< \brief 0: Start packet on a fixed time from the command start trigger<br>
//!< 1: Start packet on an external trigger (input event to RAT)
uint8_t inputMode:2; //!< \brief Input mode if external trigger is used for Tx start<br>
//!< 0: Rising edge<br>
//!< 1: Falling edge<br>
//!< 2: Both edges<br>
//!< 3: <i>Reserved</i>
uint8_t source:5; //!< RAT input event number used for capture if external trigger is used for Tx start
} startConf;
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} preTrigger; //!< Trigger for transition from preamble to sync word
ratmr_t preTime; //!< \brief Time used together with <code>preTrigger</code> for transition from preamble to sync
//!< word. If <code>preTrigger.triggerType</code> is set to "now", one preamble as
//!< configured in the setup will be sent. Otherwise, the preamble will be repeated until
//!< this trigger is observed.
uint32_t syncWord; //!< Sync word to transmit
uint8_t* pPkt; //!< Pointer to packet, or Tx queue for unlimited length
};
//! @}
//! \addtogroup CMD_PROP_RX_ADV
//! @{
#define CMD_PROP_RX_ADV 0x3804
struct __RFC_STRUCT rfc_CMD_PROP_RX_ADV_s {
uint16_t commandNo; //!< The command ID number 0x3804
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
struct {
uint8_t bFsOff:1; //!< \brief 0: Keep frequency synth on after command<br>
//!< 1: Turn frequency synth off after command
uint8_t bRepeatOk:1; //!< \brief 0: End operation after receiving a packet correctly<br>
//!< 1: Go back to sync search after receiving a packet correctly
uint8_t bRepeatNok:1; //!< \brief 0: End operation after receiving a packet with CRC error<br>
//!< 1: Go back to sync search after receiving a packet with CRC error
uint8_t bUseCrc:1; //!< \brief 0: Do not check CRC<br>
//!< 1: Check CRC
uint8_t bCrcIncSw:1; //!< \brief 0: Do not include sync word in CRC calculation<br>
//!< 1: Include sync word in CRC calculation
uint8_t bCrcIncHdr:1; //!< \brief 0: Do not include header in CRC calculation <br>
//!< 1: Include header in CRC calculation
uint8_t endType:1; //!< \brief 0: Packet is received to the end if end trigger happens after sync is obtained<br>
//!< 1: Packet reception is stopped if end trigger happens
uint8_t filterOp:1; //!< \brief 0: Stop receiver and restart sync search on address mismatch<br>
//!< 1: Receive packet and mark it as ignored on address mismatch
} pktConf;
struct {
uint8_t bAutoFlushIgnored:1; //!< If 1, automatically discard ignored packets from Rx queue
uint8_t bAutoFlushCrcErr:1; //!< If 1, automatically discard packets with CRC error from Rx queue
uint8_t :1;
uint8_t bIncludeHdr:1; //!< If 1, include the received header or length byte in the stored packet; otherwise discard it
uint8_t bIncludeCrc:1; //!< If 1, include the received CRC field in the stored packet; otherwise discard it
uint8_t bAppendRssi:1; //!< If 1, append an RSSI byte to the packet in the Rx queue
uint8_t bAppendTimestamp:1; //!< If 1, append a timestamp to the packet in the Rx queue
uint8_t bAppendStatus:1; //!< If 1, append a status byte to the packet in the Rx queue
} rxConf; //!< Rx configuration
uint32_t syncWord0; //!< Sync word to listen for
uint32_t syncWord1; //!< Alternative sync word if non-zero
uint16_t maxPktLen; //!< \brief Packet length for fixed length, maximum packet length for variable length<br>
//!< 0: Unlimited or unknown length
struct {
uint16_t numHdrBits:6; //!< Number of bits in header (0&ndash;32)
uint16_t lenPos:5; //!< Position of length field in header (0&ndash;31)
uint16_t numLenBits:5; //!< Number of bits in length field (0&ndash;16)
} hdrConf;
struct {
uint16_t addrType:1; //!< \brief 0: Address after header<br>
//!< 1: Address in header
uint16_t addrSize:5; //!< \brief If <code>addrType</code> = 0: Address size in bytes<br>
//!< If <code>addrType</code> = 1: Address size in bits
uint16_t addrPos:5; //!< \brief If <code>addrType</code> = 1: Bit position of address in header<br>
//!< If <code>addrType</code> = 0: Non-zero to extend address with sync word identifier
uint16_t numAddr:5; //!< Number of addresses in address list
} addrConf;
int8_t lenOffset; //!< Signed value to add to length field
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} endTrigger; //!< Trigger classifier for ending the operation
ratmr_t endTime; //!< Time used together with <code>endTrigger</code> for ending the operation
uint8_t* pAddr; //!< Pointer to address list
dataQueue_t* pQueue; //!< Pointer to receive queue
uint8_t* pOutput; //!< Pointer to output structure
};
//! @}
//! \addtogroup CMD_PROP_RADIO_SETUP
//! @{
#define CMD_PROP_RADIO_SETUP 0x3806
struct __RFC_STRUCT rfc_CMD_PROP_RADIO_SETUP_s {
uint16_t commandNo; //!< The command ID number 0x3806
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
struct {
uint16_t modType:3; //!< \brief 0: FSK<br>
//!< 1: GFSK<br>
//!< Others: <i>Reserved</i>
uint16_t deviation:13; //!< Deviation (250 Hz steps)
} modulation;
struct {
uint32_t preScale:4; //!< Prescaler value
uint32_t :4;
uint32_t rateWord:21; //!< Rate word
} symbolRate;
uint8_t rxBw; //!< Receiver bandwidth
struct {
uint8_t nPreamBytes:6; //!< \brief 0&ndash;30: Number of preamble bytes<br>
//!< 31: 4 preamble bits
uint8_t preamMode:2; //!< \brief 0: Send 0 as the first preamble bit<br>
//!< 1: Send 1 as the first preamble bit<br>
//!< 2: Send same first bit in preamble and sync word<br>
//!< 3: Send different first bit in preamble and sync word
} preamConf;
struct {
uint16_t nSwBits:6; //!< Number of sync word bits (up to 32)
uint16_t bBitReversal:1; //!< \brief 0: Use positive deviation for 1<br>
//!< 1: Use positive deviation for 0
uint16_t bMsbFirst:1; //!< \brief 0: Least significant bit transmitted first<br>
//!< 1: Most significant bit transmitted first
uint16_t fecMode:4; //!< \brief Select coding<br>
//!< 0: Uncoded binary modulation<br>
//!< 10: Manchester coded binary modulation<br>
//!< Others: <i>Reserved</i>
uint16_t :1;
uint16_t whitenMode:3; //!< \brief 0: No whitening<br>
//!< 1: CC1101/CC2500 compatible whitening<br>
//!< 2: PN9 whitening without byte reversal<br>
//!< 3: <i>Reserved</i><br>
//!< 4: No whitener, 32-bit IEEE 802.15.4g compatible CRC<br>
//!< 5: IEEE 802.15.4g compatible whitener and 32-bit CRC<br>
//!< 6: No whitener, dynamically IEEE 802.15.4g compatible 16-bit or 32-bit CRC<br>
//!< 7: Dynamically IEEE 802.15.4g compatible whitener and 16-bit or 32-bit CRC
} formatConf;
struct {
uint16_t frontEndMode:3; //!< \brief 0x00: Differential mode<br>
//!< 0x01: Single-ended mode RFP<br>
//!< 0x02: Single-ended mode RFN<br>
//!< 0x05 Single-ended mode RFP with external frontend control on RF pins (RFN and RXTX)<br>
//!< 0x06 Single-ended mode RFN with external frontend control on RF pins (RFP and RXTX)<br>
//!< Others: <i>Reserved</i>
uint16_t biasMode:1; //!< \brief 0: Internal bias<br>
//!< 1: External bias
uint16_t :6;
uint16_t bNoFsPowerUp:1; //!< \brief 0: Power up frequency synth<br>
//!< 1: Do not power up frequency synth
} config; //!< Configuration options
uint16_t txPower; //!< Transmit power
uint32_t* pRegOverride; //!< \brief Pointer to a list of hardware and configuration registers to override. If NULL, no
//!< override is used.
};
//! @}
//! \addtogroup CMD_PROP_RADIO_DIV_SETUP
//! @{
#define CMD_PROP_RADIO_DIV_SETUP 0x3807
struct __RFC_STRUCT rfc_CMD_PROP_RADIO_DIV_SETUP_s {
uint16_t commandNo; //!< The command ID number 0x3807
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
struct {
uint16_t modType:3; //!< \brief 0: FSK<br>
//!< 1: GFSK<br>
//!< Others: <i>Reserved</i>
uint16_t deviation:13; //!< Deviation (250 Hz steps)
} modulation;
struct {
uint32_t preScale:4; //!< Prescaler value
uint32_t :4;
uint32_t rateWord:21; //!< Rate word
} symbolRate;
uint8_t rxBw; //!< Receiver bandwidth
struct {
uint8_t nPreamBytes:6; //!< \brief 0&ndash;30: Number of preamble bytes<br>
//!< 31: 4 preamble bits
uint8_t preamMode:2; //!< \brief 0: Send 0 as the first preamble bit<br>
//!< 1: Send 1 as the first preamble bit<br>
//!< 2: Send same first bit in preamble and sync word<br>
//!< 3: Send different first bit in preamble and sync word
} preamConf;
struct {
uint16_t nSwBits:6; //!< Number of sync word bits (up to 32)
uint16_t bBitReversal:1; //!< \brief 0: Use positive deviation for 1<br>
//!< 1: Use positive deviation for 0
uint16_t bMsbFirst:1; //!< \brief 0: Least significant bit transmitted first<br>
//!< 1: Most significant bit transmitted first
uint16_t fecMode:4; //!< \brief Select coding<br>
//!< 0: Uncoded binary modulation<br>
//!< 10: Manchester coded binary modulation<br>
//!< Others: <i>Reserved</i>
uint16_t :1;
uint16_t whitenMode:3; //!< \brief 0: No whitening<br>
//!< 1: CC1101/CC2500 compatible whitening<br>
//!< 2: PN9 whitening without byte reversal<br>
//!< 3: <i>Reserved</i><br>
//!< 4: No whitener, 32-bit IEEE 802.15.4g compatible CRC<br>
//!< 5: IEEE 802.15.4g compatible whitener and 32-bit CRC<br>
//!< 6: No whitener, dynamically IEEE 802.15.4g compatible 16-bit or 32-bit CRC<br>
//!< 7: Dynamically IEEE 802.15.4g compatible whitener and 16-bit or 32-bit CRC
} formatConf;
struct {
uint16_t frontEndMode:3; //!< \brief 0x00: Differential mode<br>
//!< 0x01: Single-ended mode RFP<br>
//!< 0x02: Single-ended mode RFN<br>
//!< 0x05 Single-ended mode RFP with external frontend control on RF pins (RFN and RXTX)<br>
//!< 0x06 Single-ended mode RFN with external frontend control on RF pins (RFP and RXTX)<br>
//!< Others: <i>Reserved</i>
uint16_t biasMode:1; //!< \brief 0: Internal bias<br>
//!< 1: External bias
uint16_t :6;
uint16_t bNoFsPowerUp:1; //!< \brief 0: Power up frequency synth<br>
//!< 1: Do not power up frequency synth
} config; //!< Configuration options
uint16_t txPower; //!< Transmit power
uint32_t* pRegOverride; //!< \brief Pointer to a list of hardware and configuration registers to override. If NULL, no
//!< override is used.
uint16_t centerFreq; //!< \brief Center frequency of the frequency band used, in MHz; used for calculating some internal Tx and Rx parameters.
//!< For a single channel RF system, this should be set equal to the RF frequency used.
//!< For a multi channel RF system (e.g. frequency hopping spread spectrum), this should be set equal
//!< to the center frequency of the frequency band used.
int16_t intFreq; //!< \brief Intermediate frequency to use for Rx, in MHz on 4.12 signed format. Tx will use same
//!< intermediate frequency if supported, otherwise 0.<br>
//!< 0x8000: Use default.
uint8_t loDivider; //!< LO frequency divider setting to use. Supported values: 2, 5, 6, 10, 12, 15, and 30
};
//! @}
//! \addtogroup CMD_PROP_SET_LEN
//! @{
#define CMD_PROP_SET_LEN 0x3401
struct __RFC_STRUCT rfc_CMD_PROP_SET_LEN_s {
uint16_t commandNo; //!< The command ID number 0x3401
uint16_t rxLen; //!< Payload length to use
};
//! @}
//! \addtogroup CMD_PROP_RESTART_RX
//! @{
#define CMD_PROP_RESTART_RX 0x3402
struct __RFC_STRUCT rfc_CMD_PROP_RESTART_RX_s {
uint16_t commandNo; //!< The command ID number 0x3402
};
//! @}
//! \addtogroup propRxOutput
//! @{
//! Output structure for Rx operations
struct __RFC_STRUCT rfc_propRxOutput_s {
uint16_t nRxOk; //!< Number of packets that have been received with payload, CRC OK and not ignored
uint16_t nRxNok; //!< Number of packets that have been received with CRC error
uint8_t nRxIgnored; //!< Number of packets that have been received with CRC OK and ignored due to address mismatch
uint8_t nRxStopped; //!< Number of packets not received due to illegal length or address mismatch with pktConf.filterOp = 1
uint8_t nRxBufFull; //!< Number of packets that have been received and discarded due to lack of buffer space
int8_t lastRssi; //!< RSSI of last received packet
ratmr_t timeStamp; //!< Time stamp of last received packet
};
//! @}
//! \addtogroup propRxStatus
//! @{
//! Receive status byte that may be appended to message in receive buffer
struct __RFC_STRUCT rfc_propRxStatus_s {
struct {
uint8_t addressInd:5; //!< Index of address found (0 if not applicable)
uint8_t syncWordId:1; //!< 0 for primary sync word, 1 for alternate sync word
uint8_t result:2; //!< \brief 0: Packet received correctly, not ignored<br>
//!< 1: Packet received with CRC error<br>
//!< 2: Packet received correctly, but can be ignored<br>
//!< 3: Packet reception was aborted
} status;
};
//! @}
//! @}
//! @}
#endif /* PROP_CMD_H_ */

View file

@ -1,71 +0,0 @@
/******************************************************************************
* Filename: prop_mailbox.h
* Revised: 2015-06-29 12:59:58 +0200 (Mon, 29 Jun 2015)
* Revision: 44063
*
* Description: Definitions for proprietary mode radio interface
*
* Copyright (c) 2015, Texas Instruments Incorporated
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1) Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
*
* 2) Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* 3) Neither the name of the ORGANIZATION nor the names of its contributors may
* be used to endorse or promote products derived from this software without
* specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef PROP_MAILBOX_H_
#define PROP_MAILBOX_H_
/// \name Radio operation status
///@{
/// \name Operation finished normally
///@{
#define PROP_DONE_OK 0x3400 ///< Operation ended normally
#define PROP_DONE_RXTIMEOUT 0x3401 ///< Operation stopped after end trigger while waiting for sync
#define PROP_DONE_BREAK 0x3402 ///< Rx stopped due to time out in the middle of a packet
#define PROP_DONE_ENDED 0x3403 ///< Operation stopped after end trigger during reception
#define PROP_DONE_STOPPED 0x3404 ///< Operation stopped after stop command
#define PROP_DONE_ABORT 0x3405 ///< Operation aborted by abort command
#define PROP_DONE_RXERR 0x3406 ///< Operation ended after receiving packet with CRC error
#define PROP_DONE_IDLE 0x3407 ///< Carrier sense operation ended because of idle channel
#define PROP_DONE_BUSY 0x3408 ///< Carrier sense operation ended because of busy channel
#define PROP_DONE_IDLETIMEOUT 0x3409 ///< Carrier sense operation ended because of time out with csConf.timeoutRes = 1
#define PROP_DONE_BUSYTIMEOUT 0x340A ///< Carrier sense operation ended because of time out with csConf.timeoutRes = 0
///@}
/// \name Operation finished with error
///@{
#define PROP_ERROR_PAR 0x3800 ///< Illegal parameter
#define PROP_ERROR_RXBUF 0x3801 ///< No available Rx buffer at the start of a packet
#define PROP_ERROR_RXFULL 0x3802 ///< Out of Rx buffer during reception in a partial read buffer
#define PROP_ERROR_NO_SETUP 0x3803 ///< Radio was not set up in proprietary mode
#define PROP_ERROR_NO_FS 0x3804 ///< Synth was not programmed when running Rx or Tx
#define PROP_ERROR_RXOVF 0x3805 ///< Rx overflow observed during operation
#define PROP_ERROR_TXUNF 0x3806 ///< Tx underflow observed during operation
///@}
///@}
#endif /* PROP_MAILBOX_H_ */

View file

@ -45,6 +45,8 @@
#define DOT_15_4G_H_
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
#include "driverlib/rf_mailbox.h"
/*---------------------------------------------------------------------------*/
/* IEEE 802.15.4g frequency band identifiers (Table 68f) */
#define DOT_15_4G_FREQUENCY_BAND_169 0 /* 169.400169.475 (Europe) - 169 MHz band */
@ -81,6 +83,8 @@
#define DOT_15_4G_CHANNEL_SPACING 200
#define DOT_15_4G_CHAN0_FREQUENCY 470200
#define PROP_MODE_CONF_LO_DIVIDER 0x0A
#define SMARTRF_SETTINGS_CONF_BAND_OVERRIDES HW32_ARRAY_OVERRIDE(0x405C,1), \
(uint32_t)0x18000280,
#elif DOT_15_4G_FREQUENCY_BAND_ID==DOT_15_4G_FREQUENCY_BAND_780
#define DOT_15_4G_CHANNEL_MAX 38

View file

@ -56,6 +56,7 @@
#include "lpm.h"
#include "ti-lib.h"
#include "rf-core/rf-core.h"
#include "rf-core/rf-switch.h"
#include "rf-core/rf-ble.h"
/*---------------------------------------------------------------------------*/
/* RF core and RF HAL API */
@ -63,11 +64,11 @@
#include "hw_rfc_pwr.h"
/*---------------------------------------------------------------------------*/
/* RF Core Mailbox API */
#include "rf-core/api/mailbox.h"
#include "rf-core/api/common_cmd.h"
#include "rf-core/api/ieee_cmd.h"
#include "rf-core/api/data_entry.h"
#include "rf-core/api/ieee_mailbox.h"
#include "driverlib/rf_mailbox.h"
#include "driverlib/rf_common_cmd.h"
#include "driverlib/rf_data_entry.h"
/*---------------------------------------------------------------------------*/
#include "smartrf-settings.h"
/*---------------------------------------------------------------------------*/
@ -103,8 +104,9 @@
#define IEEE_MODE_RSSI_THRESHOLD 0xA6
#endif /* IEEE_MODE_CONF_RSSI_THRESHOLD */
/*---------------------------------------------------------------------------*/
#define STATUS_CRC_OK 0x80
#define STATUS_CORRELATION 0x7f
#define STATUS_CRC_FAIL 0x80 /* bit 7 */
#define STATUS_REJECT_FRAME 0x40 /* bit 6 */
#define STATUS_CORRELATION 0x3f /* bits 0-5 */
/*---------------------------------------------------------------------------*/
/* Data entry status field constants */
#define DATA_ENTRY_STATUS_PENDING 0x00 /* Not in use by the Radio CPU */
@ -162,29 +164,39 @@ static uint8_t rf_stats[16] = { 0 };
/* How long to wait for the RF to enter RX in rf_cmd_ieee_rx */
#define ENTER_RX_WAIT_TIMEOUT (RTIMER_SECOND >> 10)
/* How long to wait for the RF to react on CMD_ABORT: around 1 msec */
#define RF_TURN_OFF_WAIT_TIMEOUT (RTIMER_SECOND >> 10)
#define LIMITED_BUSYWAIT(cond, timeout) do { \
rtimer_clock_t end_time = RTIMER_NOW() + timeout; \
while(cond) { \
if(!RTIMER_CLOCK_LT(RTIMER_NOW(), end_time)) { \
break; \
} \
} \
} while(0)
/*---------------------------------------------------------------------------*/
/* TX Power dBm lookup table - values from SmartRF Studio */
typedef struct output_config {
radio_value_t dbm;
uint8_t register_ib;
uint8_t register_gc;
uint8_t temp_coeff;
uint16_t tx_power; /* Value for the CMD_RADIO_SETUP.txPower field */
} output_config_t;
static const output_config_t output_power[] = {
{ 5, 0x30, 0x00, 0x93 },
{ 4, 0x24, 0x00, 0x93 },
{ 3, 0x1c, 0x00, 0x5a },
{ 2, 0x18, 0x00, 0x4e },
{ 1, 0x14, 0x00, 0x42 },
{ 0, 0x21, 0x01, 0x31 },
{ -3, 0x18, 0x01, 0x25 },
{ -6, 0x11, 0x01, 0x1d },
{ -9, 0x0e, 0x01, 0x19 },
{-12, 0x0b, 0x01, 0x14 },
{-15, 0x0b, 0x03, 0x0c },
{-18, 0x09, 0x03, 0x0c },
{-21, 0x07, 0x03, 0x0c },
{ 5, 0x9330 },
{ 4, 0x9324 },
{ 3, 0x5a1c },
{ 2, 0x4e18 },
{ 1, 0x4214 },
{ 0, 0x3161 },
{ -3, 0x2558 },
{ -6, 0x1d52 },
{ -9, 0x194e },
{-12, 0x144b },
{-15, 0x0ccb },
{-18, 0x0cc9 },
{-21, 0x0cc7 },
};
#define OUTPUT_CONFIG_COUNT (sizeof(output_power) / sizeof(output_config_t))
@ -210,7 +222,7 @@ static uint64_t last_rat_timestamp64 = 0;
/* For RAT overflow handling */
static struct ctimer rat_overflow_timer;
static uint32_t rat_overflow_counter = 0;
static volatile uint32_t rat_overflow_counter = 0;
static rtimer_clock_t last_rat_overflow = 0;
/* RAT has 32-bit register, overflows once 18 minutes */
@ -261,6 +273,12 @@ volatile static uint8_t *rx_read_entry;
static uint8_t tx_buf[TX_BUF_HDR_LEN + TX_BUF_PAYLOAD_LEN] CC_ALIGN(4);
/*---------------------------------------------------------------------------*/
#ifdef IEEE_MODE_CONF_BOARD_OVERRIDES
#define IEEE_MODE_BOARD_OVERRIDES IEEE_MODE_CONF_BOARD_OVERRIDES
#else
#define IEEE_MODE_BOARD_OVERRIDES
#endif
/*---------------------------------------------------------------------------*/
/* Overrides for IEEE 802.15.4, differential mode */
static uint32_t ieee_overrides[] = {
0x00354038, /* Synth: Set RTRIM (POTAILRESTRIM) to 5 */
@ -275,6 +293,7 @@ static uint32_t ieee_overrides[] = {
0x002B50DC, /* Adjust AGC DC filter */
0x05000243, /* Increase synth programming timeout */
0x002082C3, /* Increase synth programming timeout */
IEEE_MODE_BOARD_OVERRIDES
0xFFFFFFFF, /* End of override list */
};
/*---------------------------------------------------------------------------*/
@ -340,13 +359,12 @@ transmitting(void)
* It is the caller's responsibility to make sure the RF is on. This function
* will return RF_GET_CCA_INFO_ERROR if the RF is off
*
* This function will in fact wait for a valid RSSI signal
* This function will in fact wait for a valid CCA state
*/
static uint8_t
get_cca_info(void)
{
uint32_t cmd_status;
int8_t rssi;
rfc_CMD_IEEE_CCA_REQ_t cmd;
if(!rf_is_on()) {
@ -354,9 +372,10 @@ get_cca_info(void)
return RF_GET_CCA_INFO_ERROR;
}
rssi = RF_CMD_CCA_REQ_RSSI_UNKNOWN;
memset(&cmd, 0x00, sizeof(cmd));
cmd.ccaInfo.ccaState = RF_CMD_CCA_REQ_CCA_STATE_INVALID;
while(rssi == RF_CMD_CCA_REQ_RSSI_UNKNOWN || rssi == 0) {
while(cmd.ccaInfo.ccaState == RF_CMD_CCA_REQ_CCA_STATE_INVALID) {
memset(&cmd, 0x00, sizeof(cmd));
cmd.commandNo = CMD_IEEE_CCA_REQ;
@ -365,11 +384,9 @@ get_cca_info(void)
return RF_GET_CCA_INFO_ERROR;
}
rssi = cmd.currentRssi;
}
/* We have a valid RSSI signal. Return the CCA Info */
/* We have a valid CCA state. Return the CCA Info */
return *((uint8_t *)&cmd.ccaInfo);
}
/*---------------------------------------------------------------------------*/
@ -384,9 +401,8 @@ static radio_value_t
get_rssi(void)
{
uint32_t cmd_status;
int8_t rssi;
uint8_t was_off = 0;
rfc_CMD_GET_RSSI_t cmd;
rfc_CMD_IEEE_CCA_REQ_t cmd;
/* If we are off, turn on first */
if(!rf_is_on()) {
@ -398,13 +414,19 @@ get_rssi(void)
}
memset(&cmd, 0x00, sizeof(cmd));
cmd.commandNo = CMD_GET_RSSI;
cmd.ccaInfo.ccaEnergy = RF_CMD_CCA_REQ_CCA_STATE_INVALID;
rssi = RF_CMD_CCA_REQ_RSSI_UNKNOWN;
while(cmd.ccaInfo.ccaEnergy == RF_CMD_CCA_REQ_CCA_STATE_INVALID) {
memset(&cmd, 0x00, sizeof(cmd));
cmd.commandNo = CMD_IEEE_CCA_REQ;
if(rf_core_send_cmd((uint32_t)&cmd, &cmd_status) == RF_CORE_CMD_OK) {
/* Current RSSI in bits 23:16 of cmd_status */
rssi = (cmd_status >> 16) & 0xFF;
if(rf_core_send_cmd((uint32_t)&cmd, &cmd_status) == RF_CORE_CMD_ERROR) {
PRINTF("get_rssi: CMDSTA=0x%08lx\n", cmd_status);
/* Make sure to return RSSI unknown */
cmd.currentRssi = RF_CMD_CCA_REQ_RSSI_UNKNOWN;
break;
}
}
/* If we were off, turn back off */
@ -412,7 +434,7 @@ get_rssi(void)
off();
}
return rssi;
return cmd.currentRssi;
}
/*---------------------------------------------------------------------------*/
/* Returns the current TX power in dBm */
@ -455,9 +477,7 @@ set_tx_power(radio_value_t power)
memset(&cmd, 0x00, sizeof(cmd));
cmd.commandNo = CMD_SET_TX_POWER;
cmd.txPower.IB = output_power[i].register_ib;
cmd.txPower.GC = output_power[i].register_gc;
cmd.txPower.tempCoeff = output_power[i].temp_coeff;
cmd.txPower = output_power[i].tx_power;
if(rf_core_send_cmd((uint32_t)&cmd, &cmd_status) == RF_CORE_CMD_ERROR) {
PRINTF("set_tx_power: CMDSTA=0x%08lx\n", cmd_status);
@ -470,13 +490,15 @@ rf_radio_setup()
uint32_t cmd_status;
rfc_CMD_RADIO_SETUP_t cmd;
rf_switch_select_path(RF_SWITCH_PATH_2_4GHZ);
/* Create radio setup command */
rf_core_init_radio_op((rfc_radioOp_t *)&cmd, sizeof(cmd), CMD_RADIO_SETUP);
cmd.txPower.IB = tx_power_current->register_ib;
cmd.txPower.GC = tx_power_current->register_gc;
cmd.txPower.tempCoeff = tx_power_current->temp_coeff;
cmd.txPower = tx_power_current->tx_power;
cmd.pRegOverride = ieee_overrides;
cmd.config.frontEndMode = RF_CORE_RADIO_SETUP_FRONT_END_MODE;
cmd.config.biasMode = RF_CORE_RADIO_SETUP_BIAS_MODE;
cmd.mode = 1;
/* Send Radio setup to RF Core */
@ -510,7 +532,6 @@ static uint8_t
rf_cmd_ieee_rx()
{
uint32_t cmd_status;
rtimer_clock_t t0;
int ret;
ret = rf_core_send_cmd((uint32_t)cmd_ieee_rx_buf, &cmd_status);
@ -521,10 +542,8 @@ rf_cmd_ieee_rx()
return RF_CORE_CMD_ERROR;
}
t0 = RTIMER_NOW();
while(RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) != RF_CORE_RADIO_OP_STATUS_ACTIVE &&
(RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + ENTER_RX_WAIT_TIMEOUT)));
LIMITED_BUSYWAIT(RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) != RF_CORE_RADIO_OP_STATUS_ACTIVE,
ENTER_RX_WAIT_TIMEOUT);
/* Wait to enter RX */
if(RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) != RF_CORE_RADIO_OP_STATUS_ACTIVE) {
@ -687,7 +706,7 @@ rx_off(void)
/* Continue nonetheless */
}
while(rf_is_on());
LIMITED_BUSYWAIT(rf_is_on(), RF_TURN_OFF_WAIT_TIMEOUT);
if(RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) == IEEE_DONE_STOPPED ||
RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) == IEEE_DONE_ABORT) {
@ -738,8 +757,8 @@ soft_off(void)
return;
}
while((cmd->status & RF_CORE_RADIO_OP_MASKED_STATUS) ==
RF_CORE_RADIO_OP_MASKED_STATUS_RUNNING);
LIMITED_BUSYWAIT((cmd->status & RF_CORE_RADIO_OP_MASKED_STATUS) ==
RF_CORE_RADIO_OP_MASKED_STATUS_RUNNING, RF_TURN_OFF_WAIT_TIMEOUT);
}
/*---------------------------------------------------------------------------*/
static uint8_t
@ -758,20 +777,25 @@ static const rf_core_primary_mode_t mode_ieee = {
soft_on,
};
/*---------------------------------------------------------------------------*/
static void
static uint8_t
check_rat_overflow(bool first_time)
{
static uint32_t last_value;
uint32_t current_value;
uint8_t interrupts_disabled;
/* Bail out if the RF is not on */
if(!rf_is_on()) {
return 0;
}
interrupts_disabled = ti_lib_int_master_disable();
if(first_time) {
last_value = HWREG(RFC_RAT_BASE + RATCNT);
} else {
current_value = HWREG(RFC_RAT_BASE + RATCNT);
if(current_value + RAT_RANGE / 4 < last_value) {
/* overflow detected */
/* Overflow detected */
last_rat_overflow = RTIMER_NOW();
rat_overflow_counter++;
}
@ -780,31 +804,40 @@ check_rat_overflow(bool first_time)
if(!interrupts_disabled) {
ti_lib_int_master_enable();
}
return 1;
}
/*---------------------------------------------------------------------------*/
static void
handle_rat_overflow(void *unused)
{
uint8_t success;
uint8_t was_off = 0;
if(!rf_is_on()) {
was_off = 1;
if(on() != RF_CORE_CMD_OK) {
PRINTF("overflow: on() failed\n");
ctimer_set(&rat_overflow_timer, RAT_OVERFLOW_PERIOD_SECONDS * CLOCK_SECOND / 2,
ctimer_set(&rat_overflow_timer, CLOCK_SECOND,
handle_rat_overflow, NULL);
return;
}
}
check_rat_overflow(false);
success = check_rat_overflow(false);
if(was_off) {
off();
}
if(success) {
/* Retry after half of the interval */
ctimer_set(&rat_overflow_timer, RAT_OVERFLOW_PERIOD_SECONDS * CLOCK_SECOND / 2,
handle_rat_overflow, NULL);
} else {
/* Retry sooner */
ctimer_set(&rat_overflow_timer, CLOCK_SECOND,
handle_rat_overflow, NULL);
}
}
/*---------------------------------------------------------------------------*/
static int
@ -994,7 +1027,22 @@ static uint32_t
calc_last_packet_timestamp(uint32_t rat_timestamp)
{
uint64_t rat_timestamp64;
uint32_t adjusted_overflow_counter = rat_overflow_counter;
uint32_t adjusted_overflow_counter;
uint8_t was_off = 0;
if(!rf_is_on()) {
was_off = 1;
on();
}
if(rf_is_on()) {
check_rat_overflow(false);
if(was_off) {
off();
}
}
adjusted_overflow_counter = rat_overflow_counter;
/* if the timestamp is large and the last oveflow was recently,
assume that the timestamp refers to the time before the overflow */
@ -1022,10 +1070,6 @@ read_frame(void *buf, unsigned short buf_len)
rfc_dataEntryGeneral_t *entry = (rfc_dataEntryGeneral_t *)rx_read_entry;
uint32_t rat_timestamp;
if(rf_is_on()) {
check_rat_overflow(false);
}
/* wait for entry to become finished */
rtimer_clock_t t0 = RTIMER_NOW();
while(entry->status == DATA_ENTRY_STATUS_BUSY
@ -1057,7 +1101,7 @@ read_frame(void *buf, unsigned short buf_len)
memcpy(buf, (char *)&rx_read_entry[9], len);
last_rssi = (int8_t)rx_read_entry[9 + len + 2];
last_corr_lqi = (uint8_t)rx_read_entry[9 + len + 2] & STATUS_CORRELATION;
last_corr_lqi = (uint8_t)rx_read_entry[9 + len + 3] & STATUS_CORRELATION;
/* get the timestamp */
memcpy(&rat_timestamp, (char *)rx_read_entry + 9 + len + 4, 4);
@ -1497,9 +1541,9 @@ set_value(radio_param_t param, radio_value_t value)
/* Restart the radio timer (RAT).
This causes resynchronization between RAT and RTC: useful for TSCH. */
rf_core_restart_rat();
if(rf_core_restart_rat() == RF_CORE_CMD_OK) {
check_rat_overflow(false);
}
if(rx_on() != RF_CORE_CMD_OK) {
PRINTF("set_value: rx_on() failed\n");
@ -1547,7 +1591,7 @@ get_object(radio_param_t param, void *dest, size_t size)
static radio_result_t
set_object(radio_param_t param, const void *src, size_t size)
{
radio_result_t rv;
radio_result_t rv = RADIO_RESULT_OK;
int i;
uint8_t *dst;
rfc_CMD_IEEE_RX_t *cmd = (rfc_CMD_IEEE_RX_t *)cmd_ieee_rx_buf;

View file

@ -0,0 +1,76 @@
/*
* Copyright (c) 2016, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup rf-core-prop
* @{
*
* \file
* Default TX power settings. The board can override
*/
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
#include "dev/radio.h"
#include "rf-core/prop-mode.h"
/*---------------------------------------------------------------------------*/
/* Default TX power settings for the 779-930MHz band */
const prop_mode_tx_power_config_t prop_mode_tx_power_779_930[] = {
{ 14, 0xa73f },
{ 13, 0xa63f }, /* 12.5 */
{ 12, 0xb818 },
{ 11, 0x50da },
{ 10, 0x38d3 },
{ 9, 0x2ccd },
{ 8, 0x24cb },
{ 7, 0x20c9 },
{ 6, 0x1cc7 },
{ 5, 0x18c6 },
{ 4, 0x18c5 },
{ 3, 0x14c4 },
{ 2, 0x1042 },
{ 1, 0x10c3 },
{ 0, 0x0041 },
{ -10, 0x08c0 },
{-128, 0xFFFF },
};
/*---------------------------------------------------------------------------*/
/* Default TX power settings for the 431-527MHz band */
const prop_mode_tx_power_config_t prop_mode_tx_power_431_527[] = {
{ 15, 0x003f },
{ 14, 0xbe3f }, /* 13.7 */
{ 13, 0x6a0f },
{ 10, 0x3dcb },
{ 6, 0x22c4 },
{-128, 0xFFFF },
};
/*---------------------------------------------------------------------------*/
/**
* @}
*/

View file

@ -29,11 +29,7 @@
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup rf-core
* @{
*
* \defgroup rf-core-prop CC13xx Prop mode driver
*
* \addtogroup rf-core-prop
* @{
*
* \file
@ -56,7 +52,9 @@
#include "lpm.h"
#include "ti-lib.h"
#include "rf-core/rf-core.h"
#include "rf-core/rf-switch.h"
#include "rf-core/rf-ble.h"
#include "rf-core/prop-mode.h"
#include "rf-core/dot-15-4g.h"
/*---------------------------------------------------------------------------*/
/* RF core and RF HAL API */
@ -64,14 +62,15 @@
#include "hw_rfc_pwr.h"
/*---------------------------------------------------------------------------*/
/* RF Core Mailbox API */
#include "rf-core/api/mailbox.h"
#include "rf-core/api/common_cmd.h"
#include "rf-core/api/data_entry.h"
#include "rf-core/api/prop_mailbox.h"
#include "rf-core/api/prop_cmd.h"
#include "driverlib/rf_mailbox.h"
#include "driverlib/rf_common_cmd.h"
#include "driverlib/rf_data_entry.h"
#include "driverlib/rf_prop_mailbox.h"
#include "driverlib/rf_prop_cmd.h"
/*---------------------------------------------------------------------------*/
/* CC13xxware patches */
#include "rf_patches/rf_patch_cpe_genfsk.h"
#include "rf_patches/rf_patch_rfe_genfsk.h"
/*---------------------------------------------------------------------------*/
#include "rf-core/smartrf-settings.h"
/*---------------------------------------------------------------------------*/
@ -178,40 +177,35 @@ static rfc_propRxOutput_t rx_stats;
/* How long to wait for the RF to enter RX in rf_cmd_ieee_rx */
#define ENTER_RX_WAIT_TIMEOUT (RTIMER_SECOND >> 10)
/*---------------------------------------------------------------------------*/
/* TX Power dBm lookup table - values from SmartRF Studio */
typedef struct output_config {
radio_value_t dbm;
uint16_t tx_power; /* Value for the PROP_DIV_RADIO_SETUP.txPower field */
} output_config_t;
static const output_config_t output_power[] = {
{ 14, 0xa73f },
{ 13, 0xa73f }, /* 12.5 */
{ 12, 0xb818 },
{ 11, 0x50da },
{ 10, 0x38d3 },
{ 9, 0x2ccd },
{ 8, 0x24cb },
{ 7, 0x20c9 },
{ 6, 0x1cc7 },
{ 5, 0x18c6 },
{ 4, 0x18c5 },
{ 3, 0x14c4 },
{ 2, 0x1042 },
{ 1, 0x10c3 },
{ 0, 0x0041 },
{-10, 0x08c0 },
};
#define OUTPUT_CONFIG_COUNT (sizeof(output_power) / sizeof(output_config_t))
/* TX power table for the 431-527MHz band */
#ifdef PROP_MODE_CONF_TX_POWER_431_527
#define PROP_MODE_TX_POWER_431_527 PROP_MODE_CONF_TX_POWER_431_527
#else
#define PROP_MODE_TX_POWER_431_527 prop_mode_tx_power_431_527
#endif
/*---------------------------------------------------------------------------*/
/* TX power table for the 779-930MHz band */
#ifdef PROP_MODE_CONF_TX_POWER_779_930
#define PROP_MODE_TX_POWER_779_930 PROP_MODE_CONF_TX_POWER_779_930
#else
#define PROP_MODE_TX_POWER_779_930 prop_mode_tx_power_779_930
#endif
/*---------------------------------------------------------------------------*/
/* Select power table based on the frequency band */
#if DOT_15_4G_FREQUENCY_BAND_ID==DOT_15_4G_FREQUENCY_BAND_470
#define TX_POWER_DRIVER PROP_MODE_TX_POWER_431_527
#else
#define TX_POWER_DRIVER PROP_MODE_TX_POWER_779_930
#endif
/*---------------------------------------------------------------------------*/
extern const prop_mode_tx_power_config_t TX_POWER_DRIVER[];
/* Max and Min Output Power in dBm */
#define OUTPUT_POWER_MIN (output_power[OUTPUT_CONFIG_COUNT - 1].dbm)
#define OUTPUT_POWER_MAX (output_power[0].dbm)
#define OUTPUT_POWER_MAX (TX_POWER_DRIVER[0].dbm)
#define OUTPUT_POWER_UNKNOWN 0xFFFF
/* Default TX Power - position in output_power[] */
const output_config_t *tx_power_current = &output_power[1];
const prop_mode_tx_power_config_t *tx_power_current = &TX_POWER_DRIVER[1];
/*---------------------------------------------------------------------------*/
#ifdef PROP_MODE_CONF_LO_DIVIDER
#define PROP_MODE_LO_DIVIDER PROP_MODE_CONF_LO_DIVIDER
@ -270,6 +264,7 @@ get_rssi(void)
{
uint32_t cmd_status;
int8_t rssi;
uint8_t attempts = 0;
uint8_t was_off = 0;
rfc_CMD_GET_RSSI_t cmd;
@ -282,15 +277,20 @@ get_rssi(void)
}
}
rssi = RF_CMD_CCA_REQ_RSSI_UNKNOWN;
while((rssi == RF_CMD_CCA_REQ_RSSI_UNKNOWN || rssi == 0) && ++attempts < 10) {
memset(&cmd, 0x00, sizeof(cmd));
cmd.commandNo = CMD_GET_RSSI;
rssi = RF_CMD_CCA_REQ_RSSI_UNKNOWN;
if(rf_core_send_cmd((uint32_t)&cmd, &cmd_status) == RF_CORE_CMD_OK) {
if(rf_core_send_cmd((uint32_t)&cmd, &cmd_status) == RF_CORE_CMD_ERROR) {
PRINTF("get_rssi: CMDSTA=0x%08lx\n", cmd_status);
break;
} else {
/* Current RSSI in bits 23:16 of cmd_status */
rssi = (cmd_status >> 16) & 0xFF;
}
}
/* If we were off, turn back off */
if(was_off) {
@ -337,6 +337,19 @@ set_channel(uint8_t channel)
smartrf_settings_cmd_fs.fractFreq = frac;
}
/*---------------------------------------------------------------------------*/
static uint8_t
get_tx_power_array_last_element(void)
{
const prop_mode_tx_power_config_t *array = TX_POWER_DRIVER;
uint8_t count = 0;
while(array->tx_power != OUTPUT_POWER_UNKNOWN) {
count++;
array++;
}
return count - 1;
}
/*---------------------------------------------------------------------------*/
/* Returns the current TX power in dBm */
static radio_value_t
get_tx_power(void)
@ -345,7 +358,7 @@ get_tx_power(void)
}
/*---------------------------------------------------------------------------*/
/*
* The caller must make sure to send a new CMD_PROP_RADIO_DIV_SETP to the
* The caller must make sure to send a new CMD_PROP_RADIO_DIV_SETUP to the
* radio after calling this function.
*/
static void
@ -353,14 +366,14 @@ set_tx_power(radio_value_t power)
{
int i;
for(i = OUTPUT_CONFIG_COUNT - 1; i >= 0; --i) {
if(power <= output_power[i].dbm) {
for(i = get_tx_power_array_last_element(); i >= 0; --i) {
if(power <= TX_POWER_DRIVER[i].dbm) {
/*
* Merely save the value. It will be used in all subsequent usages of
* CMD_PROP_RADIO_DIV_SETP, including one immediately after this function
* has returned
*/
tx_power_current = &output_power[i];
tx_power_current = &TX_POWER_DRIVER[i];
return;
}
@ -373,12 +386,20 @@ prop_div_radio_setup(void)
uint32_t cmd_status;
rfc_radioOp_t *cmd = (rfc_radioOp_t *)&smartrf_settings_cmd_prop_radio_div_setup;
rf_switch_select_path(RF_SWITCH_PATH_SUBGHZ);
/* Adjust loDivider depending on the selected band */
smartrf_settings_cmd_prop_radio_div_setup.loDivider = PROP_MODE_LO_DIVIDER;
/* Update to the correct TX power setting */
smartrf_settings_cmd_prop_radio_div_setup.txPower = tx_power_current->tx_power;
/* Adjust RF Front End and Bias based on the board */
smartrf_settings_cmd_prop_radio_div_setup.config.frontEndMode =
RF_CORE_PROP_FRONT_END_MODE;
smartrf_settings_cmd_prop_radio_div_setup.config.biasMode =
RF_CORE_PROP_BIAS_MODE;
/* Send Radio setup to RF Core */
if(rf_core_send_cmd((uint32_t)cmd, &cmd_status) != RF_CORE_CMD_OK) {
PRINTF("prop_div_radio_setup: DIV_SETUP, CMDSTA=0x%08lx, status=0x%04x\n",
@ -597,8 +618,6 @@ init(void)
return RF_CORE_CMD_ERROR;
}
rf_core_set_modesel();
/* Initialise RX buffers */
memset(rx_buf, 0, sizeof(rx_buf));
@ -901,7 +920,29 @@ on(void)
return RF_CORE_CMD_ERROR;
}
/* Keep track of RF Core mode */
rf_core_set_modesel();
/* Apply patches to radio core */
rf_patch_cpe_genfsk();
while(!HWREG(RFC_DBELL_BASE + RFC_DBELL_O_RFACKIFG));
HWREG(RFC_DBELL_BASE + RFC_DBELL_O_RFACKIFG) = 0;
rf_patch_rfe_genfsk();
/* Initialize bus request */
HWREG(RFC_DBELL_BASE + RFC_DBELL_O_RFACKIFG) = 0;
HWREG(RFC_DBELL_BASE + RFC_DBELL_O_CMDR) =
CMDR_DIR_CMD_1BYTE(CMD_BUS_REQUEST, 1);
/* set VCOLDO reference */
ti_lib_rfc_adi3vco_ldo_voltage_mode(true);
/* Let CC13xxware automatically set a correct value for RTRIM for us */
ti_lib_rfc_rtrim((rfc_radioOp_t *)&smartrf_settings_cmd_prop_radio_div_setup);
/* Make sure BUS_REQUEST is done */
while(!HWREG(RFC_DBELL_BASE + RFC_DBELL_O_RFACKIFG));
HWREG(RFC_DBELL_BASE + RFC_DBELL_O_RFACKIFG) = 0;
if(rf_core_start_rat() != RF_CORE_CMD_OK) {
PRINTF("on: rf_core_start_rat() failed\n");
@ -997,7 +1038,7 @@ get_value(radio_param_t param, radio_value_t *value)
*value = DOT_15_4G_CHANNEL_MAX;
return RADIO_RESULT_OK;
case RADIO_CONST_TXPOWER_MIN:
*value = OUTPUT_POWER_MIN;
*value = TX_POWER_DRIVER[get_tx_power_array_last_element()].dbm;
return RADIO_RESULT_OK;
case RADIO_CONST_TXPOWER_MAX:
*value = OUTPUT_POWER_MAX;
@ -1042,7 +1083,8 @@ set_value(radio_param_t param, radio_value_t value)
set_channel((uint8_t)value);
break;
case RADIO_PARAM_TXPOWER:
if(value < OUTPUT_POWER_MIN || value > OUTPUT_POWER_MAX) {
if(value < TX_POWER_DRIVER[get_tx_power_array_last_element()].dbm ||
value > OUTPUT_POWER_MAX) {
return RADIO_RESULT_INVALID_VALUE;
}
@ -1122,6 +1164,5 @@ const struct radio_driver prop_mode_driver = {
};
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View file

@ -0,0 +1,61 @@
/*
* Copyright (c) 2016, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup rf-core
* @{
*
* \defgroup rf-core-prop CC13xx Prop mode driver
*
* @{
*
* \file
* Header file for the CC13xx prop mode NETSTACK_RADIO driver
*/
/*---------------------------------------------------------------------------*/
#ifndef PROP_MODE_H_
#define PROP_MODE_H_
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
#include "rf-core/dot-15-4g.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
typedef struct prop_mode_tx_power_config {
radio_value_t dbm;
uint16_t tx_power; /* Value for the PROP_DIV_RADIO_SETUP.txPower field */
} prop_mode_tx_power_config_t;
/*---------------------------------------------------------------------------*/
#endif /* PROP_MODE_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View file

@ -45,9 +45,10 @@
#include "net/linkaddr.h"
#include "dev/oscillators.h"
#include "rf-core/rf-core.h"
#include "rf-core/rf-switch.h"
#include "rf-core/rf-ble.h"
#include "rf-core/api/ble_cmd.h"
#include "rf-core/api/common_cmd.h"
#include "driverlib/rf_ble_cmd.h"
#include "driverlib/rf_common_cmd.h"
#include "ti-lib.h"
/*---------------------------------------------------------------------------*/
#include <stdint.h>
@ -81,14 +82,7 @@ static uint8_t payload[BLE_ADV_PAYLOAD_BUF_LEN];
static int p = 0;
static int i;
/*---------------------------------------------------------------------------*/
typedef struct default_ble_tx_power_s {
uint16_t ib:6;
uint16_t gc:2;
uint16_t boost:1;
uint16_t temp_coeff:7;
} default_ble_tx_power_t;
static default_ble_tx_power_t tx_power = { 0x29, 0x00, 0x00, 0x00 };
static uint16_t tx_power = 0x9330;
/*---------------------------------------------------------------------------*/
/* BLE beacond config */
static struct ble_beacond_config {
@ -96,6 +90,12 @@ static struct ble_beacond_config {
char adv_name[BLE_ADV_NAME_BUF_LEN];
} beacond_config = { .interval = BLE_ADV_INTERVAL };
/*---------------------------------------------------------------------------*/
#ifdef RF_BLE_CONF_BOARD_OVERRIDES
#define RF_BLE_BOARD_OVERRIDES RF_BLE_CONF_BOARD_OVERRIDES
#else
#define RF_BLE_BOARD_OVERRIDES
#endif
/*---------------------------------------------------------------------------*/
/* BLE overrides */
static uint32_t ble_overrides[] = {
0x00364038, /* Synth: Set RTRIM (POTAILRESTRIM) to 6 */
@ -104,6 +104,7 @@ static uint32_t ble_overrides[] = {
0xEAE00603, /* Synth: Set loop bandwidth after lock to 80 kHz (K3, LSB) */
0x00010623, /* Synth: Set loop bandwidth after lock to 80 kHz (K3, MSB) */
0x00456088, /* Adjust AGC reference level */
RF_BLE_BOARD_OVERRIDES
0xFFFFFFFF, /* End of override list */
};
/*---------------------------------------------------------------------------*/
@ -217,14 +218,15 @@ rf_radio_setup()
uint32_t cmd_status;
rfc_CMD_RADIO_SETUP_t cmd;
rf_switch_select_path(RF_SWITCH_PATH_2_4GHZ);
/* Create radio setup command */
rf_core_init_radio_op((rfc_radioOp_t *)&cmd, sizeof(cmd), CMD_RADIO_SETUP);
cmd.txPower.IB = tx_power.ib;
cmd.txPower.GC = tx_power.gc;
cmd.txPower.tempCoeff = tx_power.temp_coeff;
cmd.txPower.boost = tx_power.boost;
cmd.txPower = tx_power;
cmd.pRegOverride = ble_overrides;
cmd.config.frontEndMode = RF_CORE_RADIO_SETUP_FRONT_END_MODE;
cmd.config.biasMode = RF_CORE_RADIO_SETUP_BIAS_MODE;
cmd.mode = 0;
/* Send Radio setup to RF Core */

View file

@ -45,6 +45,7 @@
#include "net/packetbuf.h"
#include "net/rime/rimestats.h"
#include "rf-core/rf-core.h"
#include "rf-core/rf-switch.h"
#include "ti-lib.h"
/*---------------------------------------------------------------------------*/
/* RF core and RF HAL API */
@ -52,15 +53,9 @@
#include "hw_rfc_pwr.h"
/*---------------------------------------------------------------------------*/
/* RF Core Mailbox API */
#include "rf-core/api/mailbox.h"
#include "rf-core/api/common_cmd.h"
#include "rf-core/api/ble_cmd.h"
#include "rf-core/api/ieee_cmd.h"
#include "rf-core/api/data_entry.h"
#include "rf-core/api/ble_mailbox.h"
#include "rf-core/api/ieee_mailbox.h"
#include "rf-core/api/prop_mailbox.h"
#include "rf-core/api/prop_cmd.h"
#include "driverlib/rf_mailbox.h"
#include "driverlib/rf_common_cmd.h"
#include "driverlib/rf_data_entry.h"
/*---------------------------------------------------------------------------*/
#include <stdint.h>
#include <stdbool.h>
@ -112,7 +107,12 @@ static bool rat_offset_known = false;
PROCESS(rf_core_process, "CC13xx / CC26xx RF driver");
/*---------------------------------------------------------------------------*/
#define RF_CORE_CLOCKS_MASK (RFC_PWR_PWMCLKEN_RFC_M | RFC_PWR_PWMCLKEN_CPE_M \
| RFC_PWR_PWMCLKEN_CPERAM_M)
| RFC_PWR_PWMCLKEN_CPERAM_M | RFC_PWR_PWMCLKEN_FSCA_M \
| RFC_PWR_PWMCLKEN_PHA_M | RFC_PWR_PWMCLKEN_RAT_M \
| RFC_PWR_PWMCLKEN_RFERAM_M | RFC_PWR_PWMCLKEN_RFE_M \
| RFC_PWR_PWMCLKEN_MDMRAM_M | RFC_PWR_PWMCLKEN_MDM_M)
/*---------------------------------------------------------------------------*/
#define RF_CMD0 0x0607
/*---------------------------------------------------------------------------*/
uint8_t
rf_core_is_accessible()
@ -261,9 +261,17 @@ rf_core_power_up()
ti_lib_int_master_enable();
}
rf_switch_power_up();
/* Let CPE boot */
HWREG(RFC_PWR_NONBUF_BASE + RFC_PWR_O_PWMCLKEN) = RF_CORE_CLOCKS_MASK;
/* Turn on additional clocks on boot */
HWREG(RFC_DBELL_BASE + RFC_DBELL_O_RFACKIFG) = 0;
HWREG(RFC_DBELL_BASE+RFC_DBELL_O_CMDR) =
CMDR_DIR_CMD_2BYTE(RF_CMD0,
RFC_PWR_PWMCLKEN_MDMRAM | RFC_PWR_PWMCLKEN_RFERAM);
/* Send ping (to verify RFCore is ready and alive) */
if(rf_core_send_cmd(CMDR_DIR_CMD(CMD_PING), &cmd_status) != RF_CORE_CMD_OK) {
PRINTF("rf_core_power_up: CMD_PING fail, CMDSTA=0x%08lx\n", cmd_status);
@ -360,6 +368,8 @@ rf_core_power_down()
while(ti_lib_prcm_power_domain_status(PRCM_DOMAIN_RFCORE)
!= PRCM_DOMAIN_POWER_OFF);
rf_switch_power_down();
ti_lib_int_pend_clear(INT_RFC_CPE_0);
ti_lib_int_pend_clear(INT_RFC_CPE_1);
ti_lib_int_enable(INT_RFC_CPE_0);
@ -419,8 +429,7 @@ rf_core_restart_rat(void)
{
if(rf_core_stop_rat() != RF_CORE_CMD_OK) {
PRINTF("rf_core_restart_rat: rf_core_stop_rat() failed\n");
return RF_CORE_CMD_ERROR;
/* Don't bail out here, still try to start it */
}
if(rf_core_start_rat() != RF_CORE_CMD_OK) {

View file

@ -52,7 +52,7 @@
#define RF_CORE_H_
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
#include "rf-core/api/common_cmd.h"
#include "driverlib/rf_common_cmd.h"
#include <stdint.h>
#include <stdbool.h>
@ -64,6 +64,45 @@
#define RF_CORE_CHANNEL 25
#endif /* RF_CORE_CONF_IEEE_MODE_CHANNEL */
/*---------------------------------------------------------------------------*/
#define RF_CORE_FRONT_END_MODE_DIFFERENTIAL 0
#define RF_CORE_FRONT_END_MODE_SINGLE_RFP 1
#define RF_CORE_FRONT_END_MODE_SINGLE_RFN 2
#define RF_CORE_BIAS_MODE_INTERNAL 0
#define RF_CORE_BIAS_MODE_EXTERNAL 1
/*---------------------------------------------------------------------------*/
/*
* RF Front-End Mode and Bias for CMD_RADIO_SETUP (IEEE and BLE)
* Default: Differential mode, internal bias
*/
#ifdef RF_CORE_CONF_RADIO_SETUP_FRONT_END_MODE
#define RF_CORE_RADIO_SETUP_FRONT_END_MODE RF_CORE_CONF_RADIO_SETUP_FRONT_END_MODE
#else
#define RF_CORE_RADIO_SETUP_FRONT_END_MODE RF_CORE_FRONT_END_MODE_DIFFERENTIAL
#endif
#ifdef RF_CORE_CONF_RADIO_SETUP_BIAS_MODE
#define RF_CORE_RADIO_SETUP_BIAS_MODE RF_CORE_CONF_RADIO_SETUP_BIAS_MODE
#else
#define RF_CORE_RADIO_SETUP_BIAS_MODE RF_CORE_BIAS_MODE_INTERNAL
#endif
/*---------------------------------------------------------------------------*/
/*
* RF Front-End Mode and Bias for CMD_PROP_DIV_RADIO_SETUP (PROP mode)
* Default: Differential mode, external bias
*/
#ifdef RF_CORE_CONF_PROP_FRONT_END_MODE
#define RF_CORE_PROP_FRONT_END_MODE RF_CORE_CONF_PROP_FRONT_END_MODE
#else
#define RF_CORE_PROP_FRONT_END_MODE RF_CORE_FRONT_END_MODE_DIFFERENTIAL
#endif
#ifdef RF_CORE_CONF_PROP_BIAS_MODE
#define RF_CORE_PROP_BIAS_MODE RF_CORE_CONF_PROP_BIAS_MODE
#else
#define RF_CORE_PROP_BIAS_MODE RF_CORE_BIAS_MODE_EXTERNAL
#endif
/*---------------------------------------------------------------------------*/
#define RF_CORE_CMD_ERROR 0
#define RF_CORE_CMD_OK 1
/*---------------------------------------------------------------------------*/

View file

@ -0,0 +1,104 @@
/*
* Copyright (c) 2016, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/** \addtogroup rf-core
* @{
*
* \defgroup rf-switch RF Switch
*
* Header file for RF switch support
*
* @{
*
* \file
* Header file with definitions related to RF switch support
*/
/*---------------------------------------------------------------------------*/
#ifndef RF_SWITCH_H_
#define RF_SWITCH_H_
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
#ifdef RF_SWITCH_CONF_PATH_2_4GHZ
#define RF_SWITCH_PATH_2_4GHZ RF_SWITCH_CONF_PATH_2_4GHZ
#else
#define RF_SWITCH_PATH_2_4GHZ 0
#endif
#ifdef RF_SWITCH_CONF_PATH_SUBGHZ
#define RF_SWITCH_PATH_SUBGHZ RF_SWITCH_CONF_PATH_SUBGHZ
#else
#define RF_SWITCH_PATH_SUBGHZ 1
#endif
/*---------------------------------------------------------------------------*/
#ifdef RF_SWITCH_CONF_ENABLE
#define RF_SWITCH_ENABLE RF_SWITCH_CONF_ENABLE
#else
#define RF_SWITCH_ENABLE 0
#endif
/*---------------------------------------------------------------------------*/
#if RF_SWITCH_ENABLE
/**
* \brief Initialise RF switch pin states.
*/
void rf_switch_init(void);
/**
* \brief Power up the RF switch.
*/
void rf_switch_power_up(void);
/**
* \brief Power down the RF switch.
*/
void rf_switch_power_down(void);
/**
* \brief Select RF path
* \param path The RF path to select on the switch.
*
* The path argument can take values RF_SWITCH_PATH_xyz
*/
void rf_switch_select_path(uint8_t path);
#else
#define rf_switch_init()
#define rf_switch_power_up()
#define rf_switch_power_down()
#define rf_switch_select_path(p)
#endif /* RF_SWITCH_ENABLE */
/*---------------------------------------------------------------------------*/
#endif /* RF_SWITCH_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View file

@ -28,38 +28,136 @@
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#include "rf-core/api/mailbox.h"
#include "rf-core/api/common_cmd.h"
#include "rf-core/api/prop_cmd.h"
#include "contiki-conf.h"
#include "rf-core/dot-15-4g.h"
#include "driverlib/rf_mailbox.h"
#include "driverlib/rf_common_cmd.h"
#include "driverlib/rf_prop_cmd.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
#ifdef SMARTRF_SETTINGS_CONF_BOARD_OVERRIDES
#define SMARTRF_SETTINGS_BOARD_OVERRIDES SMARTRF_SETTINGS_CONF_BOARD_OVERRIDES
#else
#define SMARTRF_SETTINGS_BOARD_OVERRIDES
#endif
/*---------------------------------------------------------------------------*/
#ifdef SMARTRF_SETTINGS_CONF_BAND_OVERRIDES
#define SMARTRF_SETTINGS_BAND_OVERRIDES SMARTRF_SETTINGS_CONF_BAND_OVERRIDES
#else
#define SMARTRF_SETTINGS_BAND_OVERRIDES
#endif
/*---------------------------------------------------------------------------*/
/* RSSI offset configuration for the 431-527MHz band */
#ifdef SMARTRF_SETTINGS_CONF_RSSI_OFFSET_431_527
#define SMARTRF_SETTINGS_RSSI_OFFSET_431_527 SMARTRF_SETTINGS_CONF_RSSI_OFFSET_431_527
#else
#define SMARTRF_SETTINGS_RSSI_OFFSET_431_527 0x000288A3
#endif
/*---------------------------------------------------------------------------*/
/* RSSI offset configuration for the 779-930MHz band */
#ifdef SMARTRF_SETTINGS_CONF_RSSI_OFFSET_779_930
#define SMARTRF_SETTINGS_RSSI_OFFSET_779_930 SMARTRF_SETTINGS_CONF_RSSI_OFFSET_779_930
#else
#define SMARTRF_SETTINGS_RSSI_OFFSET_779_930 0x00FB88A3
#endif
/*---------------------------------------------------------------------------*/
#ifdef SMARTRF_SETTINGS_CONF_OVERRIDE_TRIM_OFFSET
#define SMARTRF_SETTINGS_OVERRIDE_TRIM_OFFSET SMARTRF_SETTINGS_CONF_OVERRIDE_TRIM_OFFSET
#else
#define SMARTRF_SETTINGS_OVERRIDE_TRIM_OFFSET 0x00038883
#endif
/*---------------------------------------------------------------------------*/
/* Select RSSI offset value based on the frequency band */
#if DOT_15_4G_FREQUENCY_BAND_ID==DOT_15_4G_FREQUENCY_BAND_470
#define RSSI_OFFSET SMARTRF_SETTINGS_RSSI_OFFSET_431_527
#else
#define RSSI_OFFSET SMARTRF_SETTINGS_RSSI_OFFSET_779_930
#endif
/*---------------------------------------------------------------------------*/
/* Overrides for CMD_PROP_RADIO_DIV_SETUP */
uint32_t overrides[] =
static uint32_t overrides[] =
{
/* override_synth.xml */
HW32_ARRAY_OVERRIDE(0x6088, 1),
(uint32_t)0x0000001A,
ADI_HALFREG_OVERRIDE(0, 61, 0xF, 0xD),
HW32_ARRAY_OVERRIDE(0x4038, 1),
(uint32_t)0x0000003A,
/*
* override_use_patch_prop_genfsk.xml
* PHY: Use MCE ROM bank 4, RFE RAM patch
*/
MCE_RFE_OVERRIDE(0, 4, 0, 1, 0, 0),
/*
* override_synth_prop_863_930_div5.xml
* Synth: Set recommended RTRIM to 7
*/
HW_REG_OVERRIDE(0x4038, 0x0037),
/* Synth: Set Fref to 4 MHz */
(uint32_t)0x000684A3,
/* Synth: Configure fine calibration setting */
HW_REG_OVERRIDE(0x4020, 0x7F00),
/* Synth: Configure fine calibration setting */
HW_REG_OVERRIDE(0x4064, 0x0040),
(uint32_t)0x684A3,
(uint32_t)0xC0040141,
(uint32_t)0x0533B107,
(uint32_t)0xA480583,
/* Synth: Configure fine calibration setting */
(uint32_t)0xB1070503,
/* Synth: Configure fine calibration setting */
(uint32_t)0x05330523,
/* Synth: Set loop bandwidth after lock to 20 kHz */
(uint32_t)0x0A480583,
/* Synth: Set loop bandwidth after lock to 20 kHz */
(uint32_t)0x7AB80603,
ADI_REG_OVERRIDE(1, 4, 0x1F),
/*
* Synth: Configure VCO LDO
* (in ADI1, set VCOLDOCFG=0x9F to use voltage input reference)
*/
ADI_REG_OVERRIDE(1, 4, 0x9F),
/* Synth: Configure synth LDO (in ADI1, set SLDOCTL0.COMP_CAP=1) */
ADI_HALFREG_OVERRIDE(1, 7, 0x4, 0x4),
/* Synth: Use 24 MHz XOSC as synth clock, enable extra PLL filtering */
(uint32_t)0x02010403,
/* Synth: Configure extra PLL filtering */
(uint32_t)0x00108463,
/* Synth: Increase synth programming timeout (0x04B0 RAT ticks = 300 us) */
(uint32_t)0x04B00243,
/*
* override_phy_rx_aaf_bw_0xd.xml
* Rx: Set anti-aliasing filter bandwidth to 0xD
* (in ADI0, set IFAMPCTL3[7:4]=0xD)
*/
ADI_HALFREG_OVERRIDE(0, 61, 0xF, 0xD),
/*
* override_phy_gfsk_rx.xml
* Rx: Set LNA bias current trim offset. The board can override this
*/
(uint32_t)SMARTRF_SETTINGS_OVERRIDE_TRIM_OFFSET,
/* Rx: Freeze RSSI on sync found event */
HW_REG_OVERRIDE(0x6084, 0x35F1),
(uint32_t)0x00038883,
(uint32_t)0x00FB88A3,
/* TX power override */
ADI_REG_OVERRIDE(0, 12, 0xF9),
/*
* override_phy_gfsk_pa_ramp_agc_reflevel_0x1a.xml
* Tx: Enable PA ramping (0x41). Rx: Set AGC reference level to 0x1A.
*/
HW_REG_OVERRIDE(0x6088, 0x411A),
/* Tx: Configure PA ramping setting */
HW_REG_OVERRIDE(0x608C, 0x8213),
/*
* Rx: Set RSSI offset to adjust reported RSSI
* The board can override this
*/
(uint32_t)RSSI_OFFSET,
/*
* TX power override
* Tx: Set PA trim to max (in ADI0, set PACTL0=0xF8)
*/
ADI_REG_OVERRIDE(0, 12, 0xF8),
/* Overrides for CRC16 functionality */
(uint32_t)0x943,
(uint32_t)0x963,
/* Board-specific overrides, if any */
SMARTRF_SETTINGS_BOARD_OVERRIDES
/* Band-specific overrides, if any */
SMARTRF_SETTINGS_BAND_OVERRIDES
(uint32_t)0xFFFFFFFF,
};
/*---------------------------------------------------------------------------*/
@ -90,8 +188,9 @@ rfc_CMD_PROP_RADIO_DIV_SETUP_t smartrf_settings_cmd_prop_radio_div_setup =
/* 7: .4g mode with dynamic whitening and CRC choice */
.formatConf.whitenMode = 0x7,
.config.frontEndMode = 0x0, /* Differential mode */
.config.biasMode = 0x1, /* External bias*/
.config.frontEndMode = 0x00, /* Set by the driver */
.config.biasMode = 0x00, /* Set by the driver */
.config.analogCfgMode = 0x0,
.config.bNoFsPowerUp = 0x0,
.txPower = 0x00, /* Driver sets correct value */
.pRegOverride = overrides,
@ -118,9 +217,9 @@ rfc_CMD_FS_t smartrf_settings_cmd_fs =
.synthConf.bTxMode = 0x0,
.synthConf.refFreq = 0x0,
.__dummy0 = 0x00,
.midPrecal = 0x00,
.ktPrecal = 0x00,
.tdcPrecal = 0x0000,
.__dummy1 = 0x00,
.__dummy2 = 0x00,
.__dummy3 = 0x0000,
};
/*---------------------------------------------------------------------------*/
/* CMD_PROP_TX_ADV */

View file

@ -31,9 +31,9 @@
#ifndef SMARTRF_SETTINGS_H_
#define SMARTRF_SETTINGS_H_
/*---------------------------------------------------------------------------*/
#include "rf-core/api/mailbox.h"
#include "rf-core/api/common_cmd.h"
#include "rf-core/api/prop_cmd.h"
#include "driverlib/rf_mailbox.h"
#include "driverlib/rf_common_cmd.h"
#include "driverlib/rf_prop_cmd.h"
/*---------------------------------------------------------------------------*/
extern rfc_CMD_PROP_RADIO_DIV_SETUP_t smartrf_settings_cmd_prop_radio_div_setup;
extern rfc_CMD_FS_t smartrf_settings_cmd_fs;

View file

@ -391,6 +391,12 @@
#define ti_lib_pwr_ctrl_io_freeze_enable(...) PowerCtrlIOFreezeEnable(__VA_ARGS__)
#define ti_lib_pwr_ctrl_io_freeze_disable(...) PowerCtrlIOFreezeDisable(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* rfc.h */
#include "driverlib/rfc.h"
#define ti_lib_rfc_rtrim(...) RFCRTrim(__VA_ARGS__)
#define ti_lib_rfc_adi3vco_ldo_voltage_mode(...) RFCAdi3VcoLdoVoltageMode(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* sys_ctrl.h */
#include "driverlib/sys_ctrl.h"

View file

@ -0,0 +1,107 @@
/*
* Copyright (c) 2017, Robert Olsson
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
* This file is part of the Contiki operating system.
*
* Author : Robert Olsson
* roolss@kth.se & robert@radio-sensors.com
* Created : 2017-04-22
*/
/**
* \file
* A simple AES128 crypto emmgine test for Atmel radios
*/
#include "contiki.h"
#include "dev/radio.h"
#include "net/netstack.h"
#include "sys/etimer.h"
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include "rf230bb.h"
PROCESS(aes_crypto_process, "AES HW crypto process");
AUTOSTART_PROCESSES(&aes_crypto_process);
unsigned char aes_key[16] = "abcdefghijklmnop";
unsigned char aes_p[128];
unsigned char aes_c[128];
unsigned char aes_s[128];
unsigned char tmp[16];
uint8_t i;
int res;
PROCESS_THREAD(aes_crypto_process, ev, data)
{
PROCESS_BEGIN();
/* AES engine on */
NETSTACK_RADIO.on();
strcpy((char *)aes_s, "Teststring______");
for(i = 0; i < 16; i++) {
printf("%02X", aes_s[i]);
}
printf(" Uncrypted \n");
res = rf230_aes_encrypt_ebc(aes_key, aes_s, aes_c);
if(!res) {
printf("ERR encryption\n");
exit(0);
}
for(i = 0; i < 16; i++) {
printf("%02X", aes_c[i]);
}
printf(" AES-128 EBC Crypted\n");
res = rf230_aes_decrypt_ebc(aes_key, aes_c, aes_p);
if(!res) {
printf("ERR decryption\n");
exit(0);
}
for(i = 0; i < 16; i++) {
printf("%02X", aes_p[i]);
}
printf(" Decrypted \n");
res = rf230_aes_encrypt_cbc(aes_key, aes_s, sizeof(aes_s), aes_c);
if(!res) {
printf("ERR encryption\n");
exit(0);
}
for(i = 0; i < 16; i++) {
printf("%02X", aes_c[i]);
}
printf(" AES-128 MIC\n");
PROCESS_END();
}

View file

@ -0,0 +1,18 @@
CFLAGS += -DPROJECT_CONF_H=\"project-conf.h\"
CONTIKI_PROJECT = AES128HW_test
all: $(CONTIKI_PROJECT)
# We use floating vars. Add library.
PRINTF_LIB_FLT = -Wl,-u,vfprintf -lprintf_flt -lm
PRINTF_LIB_MIN = -Wl,-u,vfprintf -lprintf_min
PRINTF_LIB = $(PRINTF_LIB_FLT)
CLIBS = $(PRINTF_LIB)
CUSTOM_RULE_LINK = 1
%.$(TARGET): %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) contiki-$(TARGET).a
$(LD) $(LDFLAGS) $(TARGET_STARTFILES) ${filter-out %.a,$^} ${filter %.a,$^} $(TARGET_LIBFILES) -o $@ $(CLIBS)
CONTIKI_WITH_RIME = 1
CONTIKI = ../../..
include $(CONTIKI)/Makefile.include

View file

@ -0,0 +1,24 @@
AES128HW_test
=============
Scope
-----
Simple demo to use the AES crypto engine in the Atmel radios.
Build
-----
make TARGET=avr-rss2
Program output
--------------
*******Booting Contiki-3.x-3252-g0783591*******
I2C: AT24MAC
MAC address 7d:c2:
PAN=0xABCD, MAC=nullmac, RDC=nullrdc, NETWORK=Rime, channel=26, check-rate-Hz=128, tx-power=0
Routing Enabled
54657374737472696E675F5F5F5F5F5F Uncrypted
6FDE14E8F9453C6714B7B45B24876CBF AES-128 EBC Crypted
54657374737472696E675F5F5F5F5F5F Decrypted
215C9836DCDB443F15AFED576E9F7F72 AES-128 MIC

View file

@ -1,5 +1,5 @@
/*
* Copyright (c) 2010, Loughborough University - Computer Science
* Copyright (c) 2015, Copyright Robert Olsson / Radio Sensors AB
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@ -27,25 +27,21 @@
* SUCH DAMAGE.
*
* This file is part of the Contiki operating system.
*
*
* Author : Robert Olsson robert@radio-sensors.com
* Created : 2017-04-22
*/
/**
* \file
* Project specific configuration defines for the sniffer example.
* Project specific configuration defines for example
*
* \author
* George Oikonomou - <oikonomou@users.sourceforge.net>
* Robert Olsson - <robert@radio.sensors.com>
*/
#ifndef PROJECT_CONF_H_
#define PROJECT_CONF_H_
#define NETSTACK_CONF_MAC nullmac_driver
/* Can see other channels. Interesting. */
/* #define NETSTACK_CONF_MAC csma_driver */
#define NETSTACK_CONF_RDC stub_rdc_driver
#define AES_128_HW_CONF 1
#endif /* PROJECT_CONF_H_ */

View file

@ -39,21 +39,12 @@
*
* \defgroup cc26xx-demo CC26xx Demo Project
*
* Example project demonstrating the CC26xx platforms
* Example project demonstrating the CC13xx/CC26xx platforms
*
* This example will work for the following boards:
* - srf06-cc26xx: SmartRF06EB + CC26XX EM
* - sensortag-cc26xx: CC26XX sensortag
* - The CC2650 LaunchPad
*
* By default, the example will build for the srf06-cc26xx board. To switch
* between platforms:
* - make clean
* - make BOARD=sensortag-cc26xx savetarget
*
* or
*
* make BOARD=srf06-cc26xx savetarget
* - srf06-cc26xx: SmartRF06EB + CC13xx/CC26xx EM
* - CC2650 and CC1350 SensorTag
* - CC1310, CC1350, CC2650 LaunchPads
*
* This is an IPv6/RPL-enabled example. Thus, if you have a border router in
* your installation (same RDC layer, same PAN ID and RF channel), you should

View file

@ -55,6 +55,8 @@
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "ti-lib.h"
/*---------------------------------------------------------------------------*/
PROCESS_NAME(cetic_6lbr_client_process);
PROCESS(cc26xx_web_demo_process, "CC26XX Web Demo");
@ -85,6 +87,13 @@ static struct etimer echo_request_timer;
int def_rt_rssi = 0;
#endif
/*---------------------------------------------------------------------------*/
#if CC26XX_WEB_DEMO_ADC_DEMO
PROCESS(adc_process, "ADC process");
static uint16_t single_adc_sample;
static struct etimer et_adc;
#endif
/*---------------------------------------------------------------------------*/
process_event_t cc26xx_web_demo_publish_event;
process_event_t cc26xx_web_demo_config_loaded_event;
process_event_t cc26xx_web_demo_load_config_defaults;
@ -111,6 +120,12 @@ DEMO_SENSOR(batmon_volt, CC26XX_WEB_DEMO_SENSOR_BATMON_VOLT,
"Battery Volt", "battery-volt", "batmon_volt",
CC26XX_WEB_DEMO_UNIT_VOLT);
#if CC26XX_WEB_DEMO_ADC_DEMO
DEMO_SENSOR(adc_dio23, CC26XX_WEB_DEMO_SENSOR_ADC_DIO23,
"ADC DIO23", "adc-dio23", "adc_dio23",
CC26XX_WEB_DEMO_UNIT_VOLT);
#endif
/* Sensortag sensors */
#if BOARD_SENSORTAG
DEMO_SENSOR(bmp_pres, CC26XX_WEB_DEMO_SENSOR_BMP_PRES,
@ -467,6 +482,22 @@ get_batmon_reading(void *data)
ctimer_set(&batmon_timer, next, get_batmon_reading, NULL);
}
/*---------------------------------------------------------------------------*/
#if CC26XX_WEB_DEMO_ADC_DEMO
static void
get_adc_reading(void *data)
{
int value;
char *buf;
if(adc_dio23_reading.publish) {
value = single_adc_sample;
buf = adc_dio23_reading.converted;
memset(buf, 0, CC26XX_WEB_DEMO_CONVERTED_LEN);
snprintf(buf, CC26XX_WEB_DEMO_CONVERTED_LEN, "%d", (value * 4300) >> 12);
}
}
#endif
/*---------------------------------------------------------------------------*/
#if BOARD_SENSORTAG
/*---------------------------------------------------------------------------*/
static void
@ -825,6 +856,11 @@ init_sensors(void)
list_add(sensor_list, &batmon_temp_reading);
list_add(sensor_list, &batmon_volt_reading);
#if CC26XX_WEB_DEMO_ADC_DEMO
list_add(sensor_list, &adc_dio23_reading);
#endif
SENSORS_ACTIVATE(batmon_sensor);
#if BOARD_SENSORTAG
@ -864,6 +900,7 @@ PROCESS_THREAD(cc26xx_web_demo_process, ev, data)
/* Start all other (enabled) processes first */
process_start(&httpd_simple_process, NULL);
#if CC26XX_WEB_DEMO_COAP_SERVER
process_start(&coap_server_process, NULL);
#endif
@ -880,6 +917,10 @@ PROCESS_THREAD(cc26xx_web_demo_process, ev, data)
process_start(&net_uart_process, NULL);
#endif
#if CC26XX_WEB_DEMO_ADC_DEMO
process_start(&adc_process, NULL);
#endif
/*
* Now that processes have set their own config default values, set our
* own defaults and restore saved config from flash...
@ -967,6 +1008,56 @@ PROCESS_THREAD(cc26xx_web_demo_process, ev, data)
PROCESS_END();
}
/*---------------------------------------------------------------------------*/
#if CC26XX_WEB_DEMO_ADC_DEMO
PROCESS_THREAD(adc_process, ev, data)
{
PROCESS_BEGIN();
etimer_set(&et_adc, CLOCK_SECOND * 5);
while(1) {
PROCESS_WAIT_EVENT_UNTIL(etimer_expired(&et_adc));
/* intialisation of ADC */
ti_lib_aon_wuc_aux_wakeup_event(AONWUC_AUX_WAKEUP);
while(!(ti_lib_aon_wuc_power_status_get() & AONWUC_AUX_POWER_ON));
/*
* Enable clock for ADC digital and analog interface (not currently enabled
* in driver)
*/
ti_lib_aux_wuc_clock_enable(AUX_WUC_ADI_CLOCK | AUX_WUC_ANAIF_CLOCK |
AUX_WUC_SMPH_CLOCK);
while(ti_lib_aux_wuc_clock_status(AUX_WUC_ADI_CLOCK | AUX_WUC_ANAIF_CLOCK |
AUX_WUC_SMPH_CLOCK)
!= AUX_WUC_CLOCK_READY);
/* Connect AUX IO7 (DIO23, but also DP2 on XDS110) as analog input. */
ti_lib_aux_adc_select_input(ADC_COMPB_IN_AUXIO7);
/* Set up ADC range, AUXADC_REF_FIXED = nominally 4.3 V */
ti_lib_aux_adc_enable_sync(AUXADC_REF_FIXED, AUXADC_SAMPLE_TIME_2P7_US,
AUXADC_TRIGGER_MANUAL);
/* Trigger ADC converting */
ti_lib_aux_adc_gen_manual_trigger();
/* Read value */
single_adc_sample = ti_lib_aux_adc_read_fifo();
/* Shut the adc down */
ti_lib_aux_adc_disable();
get_adc_reading(NULL);
etimer_reset(&et_adc);
}
PROCESS_END();
}
#endif
/*---------------------------------------------------------------------------*/
/**
* @}
*/

View file

@ -79,6 +79,12 @@
#else
#define CC26XX_WEB_DEMO_NET_UART 1
#endif
#ifdef CC26XX_WEB_DEMO_CONF_ADC_DEMO
#define CC26XX_WEB_DEMO_ADC_DEMO CC26XX_WEB_DEMO_CONF_ADC_DEMO
#else
#define CC26XX_WEB_DEMO_ADC_DEMO 0
#endif
/*---------------------------------------------------------------------------*/
/* Active probing of RSSI from our preferred parent */
#if (CC26XX_WEB_DEMO_COAP_SERVER || CC26XX_WEB_DEMO_MQTT_CLIENT)
@ -146,6 +152,7 @@
#define CC26XX_WEB_DEMO_SENSOR_MPU_GYRO_X 12
#define CC26XX_WEB_DEMO_SENSOR_MPU_GYRO_Y 13
#define CC26XX_WEB_DEMO_SENSOR_MPU_GYRO_Z 14
#define CC26XX_WEB_DEMO_SENSOR_ADC_DIO23 15
/*---------------------------------------------------------------------------*/
extern process_event_t cc26xx_web_demo_publish_event;
extern process_event_t cc26xx_web_demo_config_loaded_event;

View file

@ -40,6 +40,7 @@
#include "rest-engine.h"
#include "board-peripherals.h"
#include "rf-core/rf-ble.h"
#include "cc26xx-web-demo.h"
#include <stdio.h>
#include <stdlib.h>
@ -85,6 +86,10 @@ extern resource_t res_mpu_gyro_z;
extern resource_t res_toggle_orange;
extern resource_t res_toggle_yellow;
#endif
#if CC26XX_WEB_DEMO_ADC_DEMO
extern resource_t res_adc_dio23;
#endif
/*---------------------------------------------------------------------------*/
const char *coap_server_not_found_msg = "Resource not found";
const char *coap_server_supported_msg = "Supported:"
@ -134,6 +139,10 @@ PROCESS_THREAD(coap_server_process, ev, data)
rest_activate_resource(&res_batmon_temp, "sen/batmon/temp");
rest_activate_resource(&res_batmon_volt, "sen/batmon/voltage");
#if CC26XX_WEB_DEMO_ADC_DEMO
rest_activate_resource(&res_adc_dio23, "sen/adc/dio23");
#endif
rest_activate_resource(&res_device_hw, "dev/mdl/hw");
rest_activate_resource(&res_device_sw, "dev/mdl/sw");
rest_activate_resource(&res_device_uptime, "dev/uptime");

View file

@ -137,6 +137,10 @@ PROCESS(httpd_simple_process, "CC26XX Web Server");
#define REQUEST_TYPE_GET 1
#define REQUEST_TYPE_POST 2
/*---------------------------------------------------------------------------*/
/* Temporary buffer for holding escaped HTML used by html_escape_quotes */
#define HTML_ESCAPED_BUFFER_SIZE 128
static char html_escaped_buf[HTML_ESCAPED_BUFFER_SIZE];
/*---------------------------------------------------------------------------*/
static const char *NOT_FOUND = "<html><body bgcolor=\"white\">"
"<center>"
"<h1>404 - file not found</h1>"
@ -305,6 +309,31 @@ url_unescape(const char *src, size_t srclen, char *dst, size_t dstlen)
return i == srclen;
}
/*---------------------------------------------------------------------------*/
static char*
html_escape_quotes(const char *src, size_t srclen)
{
size_t srcpos, dstpos;
memset(html_escaped_buf, 0, HTML_ESCAPED_BUFFER_SIZE);
for(srcpos = dstpos = 0;
srcpos < srclen && dstpos < HTML_ESCAPED_BUFFER_SIZE - 1; srcpos++) {
if(src[srcpos] == '\0') {
break;
} else if(src[srcpos] == '"') {
if(dstpos + 7 > HTML_ESCAPED_BUFFER_SIZE) {
break;
}
strcpy(&html_escaped_buf[dstpos], "&quot;");
dstpos += 6;
} else {
html_escaped_buf[dstpos++] = src[srcpos];
}
}
html_escaped_buf[HTML_ESCAPED_BUFFER_SIZE - 1] = '\0';
return html_escaped_buf;
}
/*---------------------------------------------------------------------------*/
void
httpd_simple_register_post_handler(httpd_simple_post_handler_t *h)
{
@ -675,7 +704,9 @@ PT_THREAD(generate_mqtt_config(struct httpd_state *s))
config_div_right));
PT_WAIT_THREAD(&s->generate_pt,
enqueue_chunk(s, 0, "value=\"%s\" ",
cc26xx_web_demo_config.mqtt_config.type_id));
html_escape_quotes(
cc26xx_web_demo_config.mqtt_config.type_id,
MQTT_CLIENT_CONFIG_TYPE_ID_LEN)));
PT_WAIT_THREAD(&s->generate_pt,
enqueue_chunk(s, 0, "name=\"type_id\">%s", config_div_close));
@ -687,7 +718,9 @@ PT_THREAD(generate_mqtt_config(struct httpd_state *s))
config_div_right));
PT_WAIT_THREAD(&s->generate_pt,
enqueue_chunk(s, 0, "value=\"%s\" ",
cc26xx_web_demo_config.mqtt_config.org_id));
html_escape_quotes(
cc26xx_web_demo_config.mqtt_config.org_id,
MQTT_CLIENT_CONFIG_ORG_ID_LEN)));
PT_WAIT_THREAD(&s->generate_pt,
enqueue_chunk(s, 0, "name=\"org_id\">%s", config_div_close));
@ -711,7 +744,9 @@ PT_THREAD(generate_mqtt_config(struct httpd_state *s))
config_div_right));
PT_WAIT_THREAD(&s->generate_pt,
enqueue_chunk(s, 0, "value=\"%s\" ",
cc26xx_web_demo_config.mqtt_config.cmd_type));
html_escape_quotes(
cc26xx_web_demo_config.mqtt_config.cmd_type,
MQTT_CLIENT_CONFIG_CMD_TYPE_LEN)));
PT_WAIT_THREAD(&s->generate_pt,
enqueue_chunk(s, 0, "name=\"cmd_type\">%s",
config_div_close));
@ -724,7 +759,9 @@ PT_THREAD(generate_mqtt_config(struct httpd_state *s))
config_div_right));
PT_WAIT_THREAD(&s->generate_pt,
enqueue_chunk(s, 0, "value=\"%s\" ",
cc26xx_web_demo_config.mqtt_config.event_type_id));
html_escape_quotes(
cc26xx_web_demo_config.mqtt_config.event_type_id,
MQTT_CLIENT_CONFIG_EVENT_TYPE_ID_LEN)));
PT_WAIT_THREAD(&s->generate_pt,
enqueue_chunk(s, 0, "name=\"event_type_id\">%s",
config_div_close));
@ -1268,9 +1305,7 @@ appcall(void *state)
if(uip_closed() || uip_aborted() || uip_timedout()) {
if(s != NULL) {
s->script = NULL;
s->blen = 0;
s->tmp_buf_len = 0;
memset(s, 0, sizeof(struct httpd_state));
memb_free(&conns, s);
}
} else if(uip_connected()) {
@ -1291,7 +1326,7 @@ appcall(void *state)
if(uip_poll()) {
if(timer_expired(&s->timer)) {
uip_abort();
s->script = NULL;
memset(s, 0, sizeof(struct httpd_state));
memb_free(&conns, s);
}
} else {

View file

@ -64,6 +64,9 @@
*/
static const char *broker_ip = "0064:ff9b:0000:0000:0000:0000:b8ac:7cbd";
/*---------------------------------------------------------------------------*/
#define ADDRESS_CONVERSION_OK 1
#define ADDRESS_CONVERSION_ERROR 0
/*---------------------------------------------------------------------------*/
/*
* A timeout used when waiting for something to happen (e.g. to connect or to
* disconnect)
@ -350,13 +353,20 @@ ip_addr_post_handler(char *key, int key_len, char *val, int val_len)
{
int rv = HTTPD_SIMPLE_POST_HANDLER_UNKNOWN;
/*
* uiplib_ip6addrconv will immediately start writing into the supplied buffer
* even if it subsequently fails. Thus, pass an intermediate buffer
*/
uip_ip6addr_t tmp_addr;
if(key_len != strlen("broker_ip") ||
strncasecmp(key, "broker_ip", strlen("broker_ip")) != 0) {
/* Not ours */
return HTTPD_SIMPLE_POST_HANDLER_UNKNOWN;
}
if(val_len > MQTT_CLIENT_CONFIG_IP_ADDR_STR_LEN) {
if(val_len > MQTT_CLIENT_CONFIG_IP_ADDR_STR_LEN
|| uiplib_ip6addrconv(val, &tmp_addr) != ADDRESS_CONVERSION_OK) {
/* Ours but bad value */
rv = HTTPD_SIMPLE_POST_HANDLER_ERROR;
} else {
@ -698,10 +708,15 @@ static void
connect_to_broker(void)
{
/* Connect to MQTT server */
mqtt_connect(&conn, conf->broker_ip, conf->broker_port,
mqtt_status_t conn_attempt_result = mqtt_connect(&conn, conf->broker_ip,
conf->broker_port,
conf->pub_interval * 3);
if(conn_attempt_result == MQTT_STATUS_OK) {
state = MQTT_CLIENT_STATE_CONNECTING;
} else {
state = MQTT_CLIENT_STATE_CONFIG_ERROR;
}
}
/*---------------------------------------------------------------------------*/
static void
@ -827,8 +842,8 @@ state_machine(void)
}
break;
case MQTT_CLIENT_STATE_NEWCONFIG:
/* Only update config after we have disconnected */
if(conn.state == MQTT_CONN_STATE_NOT_CONNECTED) {
/* Only update config after we have disconnected or in the case of an error */
if(conn.state == MQTT_CONN_STATE_NOT_CONNECTED || conn.state == MQTT_CONN_STATE_ERROR) {
update_config();
DBG("New config\n");

View file

@ -41,6 +41,13 @@
#define CC26XX_WEB_DEMO_CONF_6LBR_CLIENT 1
#define CC26XX_WEB_DEMO_CONF_COAP_SERVER 1
#define CC26XX_WEB_DEMO_CONF_NET_UART 1
/*
* ADC sensor functionality. To test this, an external voltage source should be
* connected to DIO23
* Enable/Disable DIO23 ADC reading by setting CC26XX_WEB_DEMO_CONF_ADC_DEMO
*/
#define CC26XX_WEB_DEMO_CONF_ADC_DEMO 0
/*---------------------------------------------------------------------------*/
/* Enable the ROM bootloader */
#define ROM_BOOTLOADER_ENABLE 1

View file

@ -117,6 +117,21 @@ RESOURCE(res_batmon_temp, "title=\"Battery Temp\";rt=\"C\"",
RESOURCE(res_batmon_volt, "title=\"Battery Voltage\";rt=\"mV\"",
res_get_handler_batmon_volt, NULL, NULL, NULL);
/*---------------------------------------------------------------------------*/
#if CC26XX_WEB_DEMO_ADC_DEMO
/*---------------------------------------------------------------------------*/
static void
res_get_handler_adc_dio23(void *request, void *response, uint8_t *buffer,
uint16_t preferred_size, int32_t *offset)
{
res_get_handler_all(CC26XX_WEB_DEMO_SENSOR_ADC_DIO23, request, response,
buffer, preferred_size, offset);
}
/*---------------------------------------------------------------------------*/
RESOURCE(res_adc_dio23, "title=\"ADC DIO23\";rt=\"mV\"",
res_get_handler_adc_dio23, NULL, NULL, NULL);
/*---------------------------------------------------------------------------*/
#endif
/*---------------------------------------------------------------------------*/
#if BOARD_SENSORTAG
/*---------------------------------------------------------------------------*/
/* MPU resources and handler: Accelerometer and Gyro */

View file

@ -23,7 +23,7 @@ as per the instructions below.
When the node is duty-cycling the radio, either because it is in normal mode or
because network maintenance is taking place, it will keep its green LED on thus
providing an indication that it is reachable.
providing an indication that it is reachable (red LED for the CC1350 tag).
A normal mode stint can be manually triggered by pressing the left button.

View file

@ -247,8 +247,10 @@ border_router_set_mac(const uint8_t *data)
/* is this ok - should instead remove all addresses and
add them back again - a bit messy... ?*/
PROCESS_CONTEXT_BEGIN(&tcpip_process);
uip_ds6_init();
rpl_init();
PROCESS_CONTEXT_END(&tcpip_process);
mac_set = 1;
}

View file

@ -0,0 +1,20 @@
CONTIKI_PROJECT=rf_environment
all: $(CONTIKI_PROJECT)
DEFINES+=PROJECT_CONF_H=\"project-conf.h\"
# We use floating vars. Add library.
PRINTF_LIB_FLT = -Wl,-u,vfprintf -lprintf_flt -lm
PRINTF_LIB_MIN = -Wl,-u,vfprintf -lprintf_min
PRINTF_LIB = $(PRINTF_LIB_FLT)
CLIBS = $(PRINTF_LIB)
CUSTOM_RULE_LINK = 1
%.$(TARGET): %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) contiki-$(TARGET).a
$(LD) $(LDFLAGS) $(TARGET_STARTFILES) ${filter-out %.a,$^} ${filter %.a,$^} $(TARGET_LIBFILES) -o $@ $(CLIBS)
CONTIKI=../../
include $(CONTIKI)/Makefile.include

View file

@ -0,0 +1,66 @@
Non-intrusive monitoring of the RF-environment
==============================================
rf_environment runs the clear channel assessment (CCA) test over
all 802.15.4 channels and reports stats per channel. The CCA test
is run for different CCA thresholds from -60dBm to -90dBm. CCA is
a non-destructive for the rf-environment as it's just listens.
Best and worst channel is printed as average rf activity.
See example below from Uppsala Kungs-Vaksalagatan. 2017-05-08
and Electrum Stockholm. Originally developed for the Atmel avr-rss2
platform.
Probability for not passing a CCA check in percent per channel.
3-minute samples. Of course this just snapshots to illustrate
functionality
<pre>
Chan: 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26
---------------------------------------------------------------------
cca_thresh=-82dBm 0 0 7 0 1 2 2 0 0 0 0 6 30 5 0 1 Best=11 Worst=23 Ave=3.09
cca_thresh=-80dBm 0 0 1 0 1 0 3 1 0 0 1 16 15 1 2 0 Best=11 Worst=22 Ave=2.31
cca_thresh=-78dBm 0 0 4 10 0 2 2 2 1 2 0 12 23 4 1 1 Best=11 Worst=23 Ave=3.65
cca_thresh=-76dBm 0 0 12 8 4 0 6 4 10 3 1 24 15 0 1 1 Best=11 Worst=22 Ave=5.37
cca_thresh=-74dBm 0 1 1 2 1 0 4 1 2 1 2 10 16 22 5 1 Best=11 Worst=24 Ave=3.96
cca_thresh=-72dBm 0 1 3 3 3 0 2 1 1 4 2 5 3 8 5 3 Best=11 Worst=24 Ave=2.26
cca_thresh=-70dBm 0 0 5 3 3 3 1 5 9 26 60 77 53 35 27 8 Best=11 Worst=22 Ave=19.40
cca_thresh=-68dBm 0 1 9 10 1 2 1 3 0 4 59 32 60 37 24 3 Best=11 Worst=23 Ave=14.89
cca_thresh=-66dBm 0 2 3 2 1 2 2 1 5 15 50 64 77 49 16 5 Best=11 Worst=23 Ave=17.87
cca_thresh=-64dBm 1 3 0 1 1 2 1 1 6 18 19 31 62 47 25 3 Best=13 Worst=23 Ave=13.35
cca_thresh=-62dBm 0 0 3 6 2 5 2 0 23 43 37 25 18 32 27 25 Best=11 Worst=20 Ave=15.14
cca_thresh=-60dBm 2 2 3 3 2 3 1 8 34 37 40 49 72 55 9 9 Best=17 Worst=23 Ave=20.17
cca_thresh=-90dBm 0 1 11 10 4 8 2 1 10 22 15 17 22 18 3 9 Best=11 Worst=20 Ave=9.06
cca_thresh=-88dBm 0 0 17 37 2 3 2 5 12 18 24 43 13 28 6 3 Best=11 Worst=22 Ave=12.90
cca_thresh=-86dBm 0 3 12 2 0 3 3 4 12 11 17 13 42 19 17 10 Best=11 Worst=23 Ave=10.05
cca_thresh=-84dBm 0 0 3 3 0 3 2 4 12 11 14 13 23 9 11 15 Best=11 Worst=23 Ave=7.33
cca_thresh=-82dBm 0 2 30 24 2 4 2 6 3 11 4 10 8 3 4 1 Best=11 Worst=13 Ave=6.66
cca_thresh=-80dBm 0 1 9 3 0 1 6 6 15 0 0 8 11 4 3 3 Best=11 Worst=19 Ave=4.05
cca_thresh=-78dBm 0 1 3 2 0 1 7 8 1 0 4 13 6 3 1 1 Best=11 Worst=22 Ave=2.79
cca_thresh=-76dBm 0 0 1 7 1 8 11 10 21 1 2 10 28 3 0 1 Best=11 Worst=23 Ave=6.15
cca_thresh=-74dBm 0 3 2 2 0 1 6 4 8 0 3 5 8 9 0 0 Best=11 Worst=24 Ave=2.77
cca_thresh=-72dBm 0 0 0 3 1 2 2 2 1 1 3 7 11 9 1 1 Best=11 Worst=23 Ave=2.40
cca_thresh=-70dBm 0 1 11 2 1 2 4 1 4 4 13 31 7 1 1 1 Best=11 Worst=22 Ave=4.69
cca_thresh=-68dBm 0 0 13 26 1 5 7 8 3 1 1 20 43 7 1 0 Best=11 Worst=23 Ave=8.21
cca_thresh=-66dBm 1 2 13 9 1 3 3 1 3 16 11 22 9 7 0 1 Best=25 Worst=22 Ave=5.79
cca_thresh=-64dBm 0 1 6 2 1 2 2 0 3 8 4 8 14 1 4 1 Best=11 Worst=23 Ave=3.10
cca_thresh=-62dBm 0 1 4 0 1 2 1 3 1 1 9 16 22 7 1 1 Best=11 Worst=23 Ave=3.91
cca_thresh=-60dBm 0 1 2 0 1 0 1 1 15 33 4 5 26 2 0 0 Best=11 Worst=20 Ave=5.34
cca_thresh=-90dBm 0 1 0 2 2 0 1 1 0 1 6 12 24 10 2 1 Best=11 Worst=23 Ave=3.64
cca_thresh=-88dBm 0 0 0 2 0 1 0 2 0 2 2 9 10 0 0 1 Best=11 Worst=23 Ave=1.54
Electrum Kista Stockolm (KTH/SICS etc)
cca_thresh=-62dBm 2 17 26 2 2 1 14 18 17 4 9 6 5 31 47 2 Best=16 Worst=25 Ave=12.07
cca_thresh=-60dBm 7 8 13 2 2 1 6 6 7 1 11 32 16 11 1 2 Best=16 Worst=22 Ave=7.54
cca_thresh=-90dBm 1 9 13 3 2 1 31 32 10 2 2 12 7 10 1 2 Best=11 Worst=18 Ave=8.17
cca_thresh=-88dBm 4 8 10 2 2 1 5 12 6 3 5 8 2 9 1 2 Best=16 Worst=18 Ave=4.45
cca_thresh=-86dBm 11 9 10 2 2 1 5 16 21 2 5 5 2 3 1 4 Best=25 Worst=19 Ave=5.88
cca_thresh=-84dBm 4 9 7 5 5 1 6 46 16 3 16 2 13 5 1 2 Best=25 Worst=18 Ave=8.38
cca_thresh=-82dBm 15 9 14 2 2 1 7 22 14 1 15 2 10 10 1 19 Best=25 Worst=18 Ave=8.68
cca_thresh=-80dBm 1 8 16 3 2 1 14 23 6 1 10 22 5 7 3 4 Best=11 Worst=18 Ave=7.38
cca_thresh=-78dBm 16 9 25 3 3 1 9 8 12 2 7 2 3 2 1 2 Best=16 Worst=13 Ave=6.13
cca_thresh=-76dBm 12 9 23 4 4 0 36 9 10 2 32 14 7 4 1 3 Best=16 Worst=17 Ave=10.13
cca_thresh=-74dBm 8 24 9 8 5 0 16 6 10 2 3 31 27 18 1 3 Best=16 Worst=22 Ave=10.32
cca_thresh=-72dBm 4 7 18 4 2 0 6 11 7 1 3 6 3 9 1 2 Best=16 Worst=13 Ave=4.80
</pre>

View file

@ -0,0 +1,11 @@
#ifndef PROJECT_CONF_H_
#define PROJECT_CONF_H_
#define NETSTACK_CONF_RDC nullrdc_driver
#define NETSTACK_CONF_MAC nullmac_driver
#define NETSTACK_CONF_FRAMER framer_802154
#define NETSTACK_CONF_RADIO rf230_driver
#define RS232_BAUDRATE USART_BAUD_38400
#endif /* PROJECT_CONF_H_ */

View file

@ -0,0 +1,205 @@
/*
* Copyright (c) 2016, Robert Olsson KTH Royal Institute of Technology
* COS/Kista Stockholm roolss@kth.se
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "dev/radio.h"
#include "net/netstack.h"
#include "net/packetbuf.h"
#include "sys/process.h"
#include "sys/etimer.h"
#include <dev/watchdog.h>
#include "dev/leds.h"
#include <string.h>
#include <stdint.h>
#include <stdio.h>
#define SAMPLES 1000
#define DEBUG 1
#if DEBUG
#define PRINTF(...) printf(__VA_ARGS__)
#else
#define PRINTF(...)
#endif
PROCESS(rf_scan_process, "rf_scan process");
AUTOSTART_PROCESSES(&rf_scan_process);
/*
rf_environment runs clear channel assessment (CCA) test for over
all 802.15.4 channels and reports stats per channel. The CCA test
is run for different CCA thresholds from -60 to -190 dBm. CCA is a
non-destructive for the rf-environment it's just listens.
Best and worst channel is printed as average rf activity.
Originally developed for the Atmel avr-rss2 platform.
*/
static struct etimer et;
static int cca[16], cca_thresh, chan, i, j, k;
static uint16_t best, best_sum;
static uint16_t worst, worst_sum;
static double ave;
static radio_value_t
get_chan(void)
{
radio_value_t chan;
if(NETSTACK_RADIO.get_value(RADIO_PARAM_CHANNEL, &chan) ==
RADIO_RESULT_OK) {
return chan;
}
return 0;
}
static void
set_chan(uint8_t chan)
{
if(NETSTACK_RADIO.set_value(RADIO_PARAM_CHANNEL, chan) ==
RADIO_RESULT_OK) {
}
}
static radio_value_t
get_chan_min(void)
{
radio_value_t chan;
if(NETSTACK_RADIO.get_value(RADIO_CONST_CHANNEL_MIN, &chan) ==
RADIO_RESULT_OK) {
return chan;
}
return 0;
}
static radio_value_t
get_chan_max(void)
{
radio_value_t chan;
if(NETSTACK_RADIO.get_value(RADIO_CONST_CHANNEL_MAX, &chan) ==
RADIO_RESULT_OK) {
return chan;
}
return 0;
}
static radio_value_t
get_cca_thresh(void)
{
radio_value_t cca;
if(NETSTACK_RADIO.get_value(RADIO_PARAM_CCA_THRESHOLD, &cca) ==
RADIO_RESULT_OK) {
return cca;
}
return 0;
}
static radio_value_t
set_cca_thresh(radio_value_t thresh)
{
if(NETSTACK_RADIO.set_value(RADIO_PARAM_CCA_THRESHOLD, thresh) ==
RADIO_RESULT_OK) {
return RADIO_RESULT_OK;
}
return 0;
}
void
do_all_chan_cca(int *cca, int try)
{
int j;
for(j = 0; j < 16; j++) {
set_chan(j+11);
cca[j] = 0;
#ifdef CONTIKI_TARGET_AVR_RSS2
watchdog_periodic();
#endif
NETSTACK_RADIO.on();
for(i = 0; i < try; i++) {
cca[j] += NETSTACK_RADIO.channel_clear();
}
NETSTACK_RADIO.off();
}
}
PROCESS_THREAD(rf_scan_process, ev, data)
{
PROCESS_BEGIN();
leds_init();
leds_on(LEDS_RED);
leds_on(LEDS_YELLOW);
printf("Chan min=%d\n", get_chan_min());
chan = get_chan();
printf("Chan cur=%d\n", chan);
printf("Chan max=%d\n", get_chan_max());
cca_thresh = get_cca_thresh();
printf("Default CCA thresh=%d\n", cca_thresh);
etimer_set(&et, CLOCK_SECOND / 2);
while(1) {
PROCESS_WAIT_EVENT_UNTIL(etimer_expired(&et));
for(k = -90; k <= -60; k += 2) {
set_cca_thresh(k);
do_all_chan_cca(cca, SAMPLES);
printf("cca_thresh=%-3ddBm", get_cca_thresh());
worst = 0;
worst_sum = 0xFFFF;
best = 0;
best_sum = 0;
ave = 0;
for(j = 0; j < 16; j++) {
ave += cca[j];
printf(" %3d", 100 - (100 * cca[j]) / SAMPLES);
if(cca[j] > best_sum) {
best_sum = cca[j];
best = j;
}
if(cca[j] < worst_sum) {
worst_sum = cca[j];
worst = j;
}
}
printf(" Best=%d Worst=%d Ave=%-5.2f\n", (best+11) , (worst+11), 100 - (100 * (ave / 16) / SAMPLES));
}
etimer_set(&et, CLOCK_SECOND / 2);
}
PROCESS_END();
}

View file

@ -49,6 +49,7 @@ The following radios have been tested:
* CC2538
* CC2530/CC2531
* CC1200
* RF233
Once you have the radio sorted out, you also need to configure character I/O.
The firmware captures wireless frames and streams them over a serial line to

View file

@ -0,0 +1,43 @@
/*
* Copyright (c) 2016, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#ifndef AVR_RSS2_IO_H_
#define AVR_RSS2_IO_H_
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
#include "dev/rs232.h"
#define sensniff_io_byte_out(b) rs232_send(0, b)
#define sensniff_io_flush()
#define sensniff_io_set_input(b) rs232_set_input(RS232_PORT_0, b)
/*---------------------------------------------------------------------------*/
#endif /* AVR_RSS2_IO_H_ */
/*---------------------------------------------------------------------------*/

View file

@ -0,0 +1,39 @@
/*
* Copyright (c) 2016, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#ifndef TARGET_CONF_H_
#define TARGET_CONF_H_
/*---------------------------------------------------------------------------*/
#define SENSNIFF_IO_DRIVER_H "avr-rss2/avr-rss2-io.h"
#define RS232_BAUDRATE USART_BAUD_500000
/*---------------------------------------------------------------------------*/
#endif /* TARGET_CONF_H_ */
/*---------------------------------------------------------------------------*/

View file

@ -31,6 +31,12 @@
# Author: Oliver Schmidt <ol.sc@web.de>
#
DEFINES += STATIC_MOUSE=a2e_stdmou_mou
ifdef SLIP
DEFINES += STATIC_DRIVER=a2e_ssc_ser
endif
CONTIKI_TARGET_SOURCEFILES += pfs.S
CONTIKI_CPU = $(CONTIKI)/cpu/6502
@ -57,12 +63,13 @@ disk: all
cp $(CONTIKI)/tools/$(TARGET)/prodos.dsk contiki.dsk
java -jar $(AC) -p contiki.dsk contiki.system sys < $(CC65_TARGET_DIR)/util/loader.system
java -jar $(AC) -cc65 contiki.dsk contiki bin < $(CONTIKI_PROJECT).$(TARGET)
ifdef SLIP
java -jar $(AC) -p contiki.dsk contiki.cfg bin 0 < $(CONTIKI)/tools/6502/sample.cfg
else
java -jar $(AC) -p contiki.dsk contiki.cfg bin 0 < $(CONTIKI)/tools/$(TARGET)/sample.cfg
java -jar $(AC) -p contiki.dsk cs8900a.eth rel 0 < cs8900a.eth
java -jar $(AC) -p contiki.dsk lan91c96.eth rel 0 < lan91c96.eth
java -jar $(AC) -p contiki.dsk w5100.eth rel 0 < w5100.eth
ifeq ($(findstring WITH_MOUSE,$(DEFINES)),WITH_MOUSE)
java -jar $(AC) -p contiki.dsk contiki.mou rel 0 < $(CC65_TARGET_DIR)/drv/mou/a2e.stdmou.mou
endif
ifeq ($(HTTPD-CFS),1)
java -jar $(AC) -p contiki.dsk index.htm bin 0 < httpd-cfs/index.htm

View file

@ -36,8 +36,19 @@
#include "ctk/ctk.h"
#include "sys/log.h"
#include "lib/config.h"
#include "dev/slip.h"
#include "net/ethernet-drv.h"
#if WITH_SLIP
#define DRIVER_PROCESS &slip_process,
#define SLIP_INIT() slip_arch_init(0)
#define SLIP_POLL() slip_arch_poll()
#else /* WITH_SLIP */
#define DRIVER_PROCESS &ethernet_process,
#define SLIP_INIT()
#define SLIP_POLL()
#endif /* WITH_SLIP */
#if WITH_GUI
#define CTK_PROCESS &ctk_process,
#else /* WITH_GUI */
@ -52,12 +63,12 @@
PROCINIT(&etimer_process,
CTK_PROCESS
DRIVER_PROCESS
&tcpip_process
RESOLV_PROCESS);
static struct ethernet_config *ethernet_config;
void clock_update(void);
void slip_arch_poll(void);
/*-----------------------------------------------------------------------------------*/
#if WITH_ARGS
@ -87,35 +98,12 @@ main(void)
videomode(VIDEOMODE_80COL);
#endif /* WITH_80COL */
config_read("contiki.cfg");
SLIP_INIT();
process_init();
#if 1
ethernet_config = config_read("contiki.cfg");
#else
{
static struct ethernet_config config = {0xC0B0, "cs8900a.eth"};
uip_ipaddr_t addr;
uip_ipaddr(&addr, 192,168,0,128);
uip_sethostaddr(&addr);
uip_ipaddr(&addr, 255,255,255,0);
uip_setnetmask(&addr);
uip_ipaddr(&addr, 192,168,0,1);
uip_setdraddr(&addr);
uip_ipaddr(&addr, 192,168,0,1);
uip_nameserver_update(&addr, UIP_NAMESERVER_INFINITE_LIFETIME);
ethernet_config = &config;
}
#endif
procinit_init();
process_start((struct process *)&ethernet_process, (void *)ethernet_config);
autostart_start(autostart_processes);
log_message("Contiki up and running ...", "");
@ -126,6 +114,8 @@ main(void)
etimer_request_poll();
SLIP_POLL();
clock_update();
}
}

Some files were not shown because too many files have changed in this diff Show more