mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-06-04 05:42:49 +08:00
Merge branch 'master' of https://github.com/paparazzi/paparazzi
This commit is contained in:
@@ -17,7 +17,7 @@
|
||||
<define name="USE_$(EXTRA_DL_PORT_UPPER)"/>
|
||||
<define name="$(EXTRA_DL_PORT_UPPER)_BAUD" value="$(EXTRA_DL_BAUD)"/>
|
||||
<file name="extra_pprz_dl.c"/>
|
||||
<file name="pprz_transport.c" dir="subsystems/datalink"/>
|
||||
<file name="pprz_transport.c" dir="$(PAPARAZZI_HOME)/var/share/pprzlink/src"/>
|
||||
</makefile>
|
||||
</module>
|
||||
|
||||
|
||||
@@ -240,7 +240,7 @@ void uart_periph_set_baudrate(struct uart_periph *periph, uint32_t baud)
|
||||
}
|
||||
}
|
||||
|
||||
void uart_put_byte(struct uart_periph *periph, uint8_t data)
|
||||
void uart_put_byte(struct uart_periph *periph, long fd __attribute__((unused)), uint8_t data)
|
||||
{
|
||||
if (periph->reg_addr == NULL) { return; } // device not initialized ?
|
||||
|
||||
|
||||
@@ -139,7 +139,7 @@ void udp_receive(struct udp_periph *p)
|
||||
/**
|
||||
* Send a message
|
||||
*/
|
||||
void udp_send_message(struct udp_periph *p)
|
||||
void udp_send_message(struct udp_periph *p, long fd __attribute__((unused)))
|
||||
{
|
||||
if (p == NULL) return;
|
||||
if (p->network == NULL) return;
|
||||
@@ -165,7 +165,7 @@ void udp_send_message(struct udp_periph *p)
|
||||
/**
|
||||
* Send a packet from another buffer
|
||||
*/
|
||||
void udp_send_raw(struct udp_periph *p, uint8_t *buffer, uint16_t size)
|
||||
void udp_send_raw(struct udp_periph *p, long fd __attribute__((unused)), uint8_t *buffer, uint16_t size)
|
||||
{
|
||||
if (p == NULL) return;
|
||||
if (p->network == NULL) return;
|
||||
|
||||
@@ -105,12 +105,12 @@ static void SSP_ISR(void) __attribute__((naked));
|
||||
|
||||
|
||||
// Functions for the generic device API
|
||||
static int spi_slave_hs_check_free_space(struct spi_slave_hs *p __attribute__((unused)), uint8_t len __attribute__((unused)))
|
||||
static int spi_slave_hs_check_free_space(struct spi_slave_hs *p __attribute__((unused)), long *fd __attribute__((unused)), uint16_t len __attribute__((unused)))
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
static void spi_slave_hs_transmit(struct spi_slave_hs *p __attribute__((unused)), uint8_t byte)
|
||||
static void spi_slave_hs_transmit(struct spi_slave_hs *p __attribute__((unused)), long fd __attribute__((unused)), uint8_t byte)
|
||||
{
|
||||
uint8_t temp = (spi_slave_hs_tx_insert_idx + 1) % SPI_SLAVE_HS_TX_BUFFER_SIZE;
|
||||
if (temp != spi_slave_hs_tx_extract_idx) /* there is room left */
|
||||
@@ -120,7 +120,15 @@ static void spi_slave_hs_transmit(struct spi_slave_hs *p __attribute__((unused))
|
||||
}
|
||||
}
|
||||
|
||||
static void spi_slave_hs_send(struct spi_slave_hs *p __attribute__((unused))) { }
|
||||
static void spi_slave_hs_transmit_buffer(struct spi_slave_hs *p __attribute__((unused)), long fd, uint8_t *data, uint16_t len)
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < len; i++) {
|
||||
spi_slave_hs_transmit(p, fd, data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
static void spi_slave_hs_send(struct spi_slave_hs *p __attribute__((unused)), long fd __attribute__((unused))) { }
|
||||
|
||||
static int spi_slave_hs_char_available(struct spi_slave_hs *p __attribute__((unused)))
|
||||
{
|
||||
@@ -164,6 +172,7 @@ void spi_slave_hs_init(void)
|
||||
spi_slave_hs.device.periph = (void *)(&spi_slave_hs);
|
||||
spi_slave_hs.device.check_free_space = (check_free_space_t) spi_slave_hs_check_free_space;
|
||||
spi_slave_hs.device.put_byte = (put_byte_t) spi_slave_hs_transmit;
|
||||
spi_slave_hs.device.put_buffer = (put_buffer_t) spi_slave_hs_transmit_buffer;
|
||||
spi_slave_hs.device.send_message = (send_message_t) spi_slave_hs_send;
|
||||
spi_slave_hs.device.char_available = (char_available_t) spi_slave_hs_char_available;
|
||||
spi_slave_hs.device.get_byte = (get_byte_t) spi_slave_hs_getch;
|
||||
|
||||
@@ -80,7 +80,7 @@ void uart_periph_set_bits_stop_parity(struct uart_periph *p __attribute__((unuse
|
||||
// TBD
|
||||
}
|
||||
|
||||
void uart_put_byte(struct uart_periph *p, uint8_t data)
|
||||
void uart_put_byte(struct uart_periph *p, long fd __attribute__((unused)), uint8_t data)
|
||||
{
|
||||
uint16_t temp;
|
||||
unsigned cpsr;
|
||||
|
||||
@@ -406,7 +406,7 @@ int VCOM_getchar(void)
|
||||
|
||||
@returns TRUE if len bytes are free
|
||||
*/
|
||||
bool VCOM_check_free_space(uint8_t len)
|
||||
bool VCOM_check_free_space(uint16_t len)
|
||||
{
|
||||
return (fifo_free(&txfifo) >= len ? TRUE : FALSE);
|
||||
}
|
||||
@@ -547,17 +547,25 @@ static void USBFrameHandler(U16 wFrame __attribute__((unused)))
|
||||
struct usb_serial_periph usb_serial;
|
||||
|
||||
// Functions for the generic device API
|
||||
static int usb_serial_check_free_space(struct usb_serial_periph *p __attribute__((unused)), uint8_t len)
|
||||
static int usb_serial_check_free_space(struct usb_serial_periph *p __attribute__((unused)), long *fd __attribute__((unused)), uint8_t len)
|
||||
{
|
||||
return (int)VCOM_check_free_space(len);
|
||||
}
|
||||
|
||||
static void usb_serial_transmit(struct usb_serial_periph *p __attribute__((unused)), uint8_t byte)
|
||||
static void usb_serial_transmit(struct usb_serial_periph *p __attribute__((unused)), long fd __attribute__((unused)), uint8_t byte)
|
||||
{
|
||||
VCOM_putchar(byte);
|
||||
}
|
||||
|
||||
static void usb_serial_send(struct usb_serial_periph *p __attribute__((unused))) { }
|
||||
static void usb_serial_transmit_buffer(struct usb_serial_periph *p __attribute__((unused)), long fd __attribute__((unused)), uint8_t *data, uint16_t len)
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < len; i++) {
|
||||
VCOM_putchar(data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
static void usb_serial_send(struct usb_serial_periph *p __attribute__((unused)), long fd __attribute__((unused))) { }
|
||||
|
||||
// Empty for lpc21
|
||||
void VCOM_event(void) {}
|
||||
@@ -619,6 +627,7 @@ void VCOM_init(void)
|
||||
usb_serial.device.periph = (void *)(&usb_serial);
|
||||
usb_serial.device.check_free_space = (check_free_space_t) usb_serial_check_free_space;
|
||||
usb_serial.device.put_byte = (put_byte_t) usb_serial_transmit;
|
||||
usb_serial.device.put_buffer = (put_buffer_t) usb_serial_transmit_buffer;
|
||||
usb_serial.device.send_message = (send_message_t) usb_serial_send;
|
||||
usb_serial.device.char_available = (char_available_t) usb_serial_char_available;
|
||||
usb_serial.device.get_byte = (get_byte_t) usb_serial_getch;
|
||||
|
||||
@@ -109,7 +109,7 @@ void uart_periph_set_mode(struct uart_periph *p, bool tx_enabled, bool rx_enable
|
||||
}
|
||||
}
|
||||
|
||||
void uart_put_byte(struct uart_periph *p, uint8_t data)
|
||||
void uart_put_byte(struct uart_periph *p, long fd __attribute__((unused)), uint8_t data)
|
||||
{
|
||||
|
||||
uint16_t temp = (p->tx_insert_idx + 1) % UART_TX_BUFFER_SIZE;
|
||||
|
||||
@@ -500,17 +500,30 @@ struct usb_serial_periph usb_serial;
|
||||
|
||||
// Functions for the generic device API
|
||||
static int usb_serial_check_free_space(struct usb_serial_periph *p __attribute__((unused)),
|
||||
long *fd __attribute__((unused)),
|
||||
uint8_t len)
|
||||
{
|
||||
return (int)VCOM_check_free_space(len);
|
||||
}
|
||||
|
||||
static void usb_serial_transmit(struct usb_serial_periph *p __attribute__((unused)), uint8_t byte)
|
||||
static void usb_serial_transmit(struct usb_serial_periph *p __attribute__((unused)),
|
||||
long fd __attribute__((unused)),
|
||||
uint8_t byte)
|
||||
{
|
||||
VCOM_putchar(byte);
|
||||
}
|
||||
|
||||
static void usb_serial_send(struct usb_serial_periph *p __attribute__((unused)))
|
||||
static void usb_serial_transmit_buffer(struct usb_serial_periph *p __attribute__((unused)),
|
||||
long fd __attribute__((unused)),
|
||||
uint8_t *data, uint16_t len)
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < len; i++) {
|
||||
VCOM_putchar(data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
static void usb_serial_send(struct usb_serial_periph *p __attribute__((unused)), long fd __attribute__((unused)))
|
||||
{
|
||||
VCOM_send_message();
|
||||
}
|
||||
@@ -558,9 +571,11 @@ void VCOM_init(void)
|
||||
usb_serial.device.periph = (void *)(&usb_serial);
|
||||
usb_serial.device.check_free_space = (check_free_space_t) usb_serial_check_free_space;
|
||||
usb_serial.device.put_byte = (put_byte_t) usb_serial_transmit;
|
||||
usb_serial.device.put_buffer = (put_buffer_t) usb_serial_transmit_buffer;
|
||||
usb_serial.device.send_message = (send_message_t) usb_serial_send;
|
||||
usb_serial.device.char_available = (char_available_t) usb_serial_char_available;
|
||||
usb_serial.device.get_byte = (get_byte_t) usb_serial_getch;
|
||||
|
||||
tx_timeout = 0;
|
||||
}
|
||||
|
||||
|
||||
@@ -36,12 +36,12 @@
|
||||
|
||||
static inline void autopilot_parse(char c)
|
||||
{
|
||||
ModemLinkDevice->put_byte(ModemLinkDevice->periph, c);
|
||||
ModemLinkDevice->put_byte(ModemLinkDevice->periph, 0, c);
|
||||
}
|
||||
|
||||
static inline void modem_parse(char c)
|
||||
{
|
||||
AutopilotLinkDevice->put_byte(AutopilotLinkDevice->periph, c);
|
||||
AutopilotLinkDevice->put_byte(AutopilotLinkDevice->periph, 0, c);
|
||||
}
|
||||
|
||||
void fbw_datalink_periodic(void)
|
||||
|
||||
@@ -74,13 +74,14 @@ static inline void tunnel_event(void)
|
||||
inc = uart_getch(&USB_TUNNEL_UART);
|
||||
VCOM_putchar(inc);
|
||||
}
|
||||
if (VCOM_check_available() && uart_check_free_space(&USB_TUNNEL_UART, 1)) {
|
||||
long fd = 0;
|
||||
if (VCOM_check_available() && uart_check_free_space(&USB_TUNNEL_UART, &fd, 1)) {
|
||||
#if LED_AVAILABLE(TUNNEL_TX_LED)
|
||||
LED_ON(TUNNEL_TX_LED);
|
||||
tx_time = get_sys_time_msec();
|
||||
#endif
|
||||
inc = VCOM_getchar();
|
||||
uart_put_byte(&USB_TUNNEL_UART, inc);
|
||||
uart_put_byte(&USB_TUNNEL_UART, fd, inc);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -31,7 +31,7 @@
|
||||
|
||||
// Use uart interface directly
|
||||
#define InterMcuBuffer() uart_char_available(&(INTERMCU_LINK))
|
||||
#define InterMcuUartSend1(c) uart_put_byte(&(INTERMCU_LINK), c)
|
||||
#define InterMcuUartSend1(c) uart_put_byte(&(INTERMCU_LINK), 0, c)
|
||||
#define InterMcuUartSetBaudrate(_a) uart_periph_set_baudrate(&(INTERMCU_LINK), _a)
|
||||
#define InterMcuUartSendMessage() {}
|
||||
#define InterMcuUartGetch() uart_getch(&(INTERMCU_LINK))
|
||||
|
||||
@@ -228,8 +228,6 @@ static void send_uart_err(struct transport_tx *trans __attribute__ ((unused)),
|
||||
}
|
||||
#endif
|
||||
|
||||
static void null_function(struct uart_periph *p __attribute__((unused))) {}
|
||||
|
||||
void uart_periph_init(struct uart_periph *p)
|
||||
{
|
||||
p->rx_insert_idx = 0;
|
||||
@@ -241,12 +239,13 @@ void uart_periph_init(struct uart_periph *p)
|
||||
p->ne_err = 0;
|
||||
p->fe_err = 0;
|
||||
p->device.periph = (void *)p;
|
||||
p->device.check_free_space = (check_free_space_t)uart_check_free_space;
|
||||
p->device.put_byte = (put_byte_t)uart_put_byte;
|
||||
p->device.send_message = (send_message_t)null_function;
|
||||
p->device.char_available = (char_available_t)uart_char_available;
|
||||
p->device.get_byte = (get_byte_t)uart_getch;
|
||||
p->device.set_baudrate = (set_baudrate_t)uart_periph_set_baudrate;
|
||||
p->device.check_free_space = (check_free_space_t) uart_check_free_space;
|
||||
p->device.put_byte = (put_byte_t) uart_put_byte;
|
||||
p->device.put_buffer = (put_buffer_t) uart_put_buffer;
|
||||
p->device.send_message = (send_message_t) uart_send_message;
|
||||
p->device.char_available = (char_available_t) uart_char_available;
|
||||
p->device.get_byte = (get_byte_t) uart_getch;
|
||||
p->device.set_baudrate = (set_baudrate_t) uart_periph_set_baudrate;
|
||||
|
||||
#if PERIODIC_TELEMETRY
|
||||
// the first to register do it for the others
|
||||
@@ -254,7 +253,7 @@ void uart_periph_init(struct uart_periph *p)
|
||||
#endif
|
||||
}
|
||||
|
||||
bool uart_check_free_space(struct uart_periph *p, uint8_t len)
|
||||
bool WEAK uart_check_free_space(struct uart_periph *p, long *fd __attribute__((unused)), uint16_t len)
|
||||
{
|
||||
int16_t space = p->tx_extract_idx - p->tx_insert_idx;
|
||||
if (space <= 0) {
|
||||
@@ -263,6 +262,20 @@ bool uart_check_free_space(struct uart_periph *p, uint8_t len)
|
||||
return (uint16_t)(space - 1) >= len;
|
||||
}
|
||||
|
||||
// Weak implementation of put_buffer, byte by byte
|
||||
void WEAK uart_put_buffer(struct uart_periph *p, long fd, const uint8_t *data, uint16_t len)
|
||||
{
|
||||
int i = 0;
|
||||
for (i = 0; i < len; i++) {
|
||||
uart_put_byte(p, fd, data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
// Weak implementation of send_message, not needed for stream operation
|
||||
void WEAK uart_send_message(struct uart_periph *p __attribute__((unused)), long fd __attribute__((unused)))
|
||||
{
|
||||
}
|
||||
|
||||
uint8_t WEAK uart_getch(struct uart_periph *p)
|
||||
{
|
||||
uint8_t ret = p->rx_buf[p->rx_extract_idx];
|
||||
@@ -282,3 +295,4 @@ uint16_t WEAK uart_char_available(struct uart_periph *p)
|
||||
void WEAK uart_arch_init(void)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
@@ -95,8 +95,10 @@ extern void uart_periph_init(struct uart_periph *p);
|
||||
extern void uart_periph_set_baudrate(struct uart_periph *p, uint32_t baud);
|
||||
extern void uart_periph_set_bits_stop_parity(struct uart_periph *p, uint8_t bits, uint8_t stop, uint8_t parity);
|
||||
extern void uart_periph_set_mode(struct uart_periph *p, bool tx_enabled, bool rx_enabled, bool hw_flow_control);
|
||||
extern void uart_put_byte(struct uart_periph *p, uint8_t data);
|
||||
extern bool uart_check_free_space(struct uart_periph *p, uint8_t len);
|
||||
extern void uart_put_byte(struct uart_periph *p, long fd, uint8_t data);
|
||||
extern void uart_put_buffer(struct uart_periph *p, long fd, const uint8_t *data, uint16_t len);
|
||||
extern bool uart_check_free_space(struct uart_periph *p, long *fd, uint16_t len);
|
||||
extern void uart_send_message(struct uart_periph *p, long fd);
|
||||
extern uint8_t uart_getch(struct uart_periph *p);
|
||||
|
||||
/**
|
||||
|
||||
@@ -63,6 +63,7 @@ void udp_periph_init(struct udp_periph *p, char *host, int port_out, int port_in
|
||||
p->device.periph = (void *)p;
|
||||
p->device.check_free_space = (check_free_space_t) udp_check_free_space;
|
||||
p->device.put_byte = (put_byte_t) udp_put_byte;
|
||||
p->device.put_buffer = (put_buffer_t) udp_send_raw;
|
||||
p->device.send_message = (send_message_t) udp_send_message;
|
||||
p->device.char_available = (char_available_t) udp_char_available;
|
||||
p->device.get_byte = (get_byte_t) udp_getch;
|
||||
@@ -77,7 +78,7 @@ void udp_periph_init(struct udp_periph *p, char *host, int port_out, int port_in
|
||||
* @param len how many bytes of free space to check for
|
||||
* @return TRUE if enough space for len bytes
|
||||
*/
|
||||
bool udp_check_free_space(struct udp_periph *p, uint8_t len)
|
||||
bool WEAK udp_check_free_space(struct udp_periph *p, long *fd __attribute__((unused)), uint16_t len)
|
||||
{
|
||||
return (UDP_TX_BUFFER_SIZE - p->tx_insert_idx) >= len;
|
||||
}
|
||||
@@ -87,7 +88,7 @@ bool udp_check_free_space(struct udp_periph *p, uint8_t len)
|
||||
* @param p pointer to UDP peripheral
|
||||
* @param data byte to add to tx buffer
|
||||
*/
|
||||
void udp_put_byte(struct udp_periph *p, uint8_t data)
|
||||
void WEAK udp_put_byte(struct udp_periph *p, long fd __attribute__((unused)), uint8_t data)
|
||||
{
|
||||
if (p->tx_insert_idx >= UDP_TX_BUFFER_SIZE) {
|
||||
return; // no room
|
||||
|
||||
@@ -49,14 +49,14 @@ struct udp_periph {
|
||||
struct link_device device;
|
||||
};
|
||||
|
||||
extern void udp_periph_init(struct udp_periph *p, char *host, int port_out, int port_in, bool broadcast);
|
||||
extern bool udp_check_free_space(struct udp_periph *p, uint8_t len);
|
||||
extern void udp_put_byte(struct udp_periph *p, uint8_t data);
|
||||
extern void udp_periph_init(struct udp_periph *p, char *host, int port_out, int port_in, bool_t broadcast);
|
||||
extern bool udp_check_free_space(struct udp_periph *p, long *fd, uint16_t len);
|
||||
extern void udp_put_byte(struct udp_periph *p, long fd, uint8_t data);
|
||||
extern uint16_t udp_char_available(struct udp_periph *p);
|
||||
extern uint8_t udp_getch(struct udp_periph *p);
|
||||
extern void udp_arch_periph_init(struct udp_periph *p, char *host, int port_out, int port_in, bool broadcast);
|
||||
extern void udp_send_message(struct udp_periph *p);
|
||||
extern void udp_send_raw(struct udp_periph *p, uint8_t *buffer, uint16_t size);
|
||||
extern void udp_send_message(struct udp_periph *p, long fd);
|
||||
extern void udp_send_raw(struct udp_periph *p, long fd, uint8_t *buffer, uint16_t size);
|
||||
extern void udp_receive(struct udp_periph *p);
|
||||
|
||||
#if USE_UDP0
|
||||
|
||||
@@ -42,7 +42,7 @@ extern struct usb_serial_periph usb_serial;
|
||||
void VCOM_init(void);
|
||||
int VCOM_putchar(int c);
|
||||
int VCOM_getchar(void);
|
||||
bool VCOM_check_free_space(uint8_t len);
|
||||
bool VCOM_check_free_space(uint16_t len);
|
||||
int VCOM_check_available(void);
|
||||
void VCOM_set_linecoding(uint8_t mode);
|
||||
void VCOM_allow_linecoding(uint8_t mode);
|
||||
|
||||
@@ -31,7 +31,7 @@ static uint8_t drop_string[] = "<Drop_Paintball_Now";
|
||||
|
||||
void drop_ball(uint8_t number) {
|
||||
for(uint8_t i = 0; i < DROP_STRINGLEN; i++)
|
||||
uart_put_byte(&UART_DROP_PORT, drop_string[i]);
|
||||
uart_put_byte(&UART_DROP_PORT, 0, drop_string[i]);
|
||||
|
||||
uint8_t last = '>';
|
||||
if(number == 1) {
|
||||
@@ -43,5 +43,5 @@ void drop_ball(uint8_t number) {
|
||||
} else if(number == 4) {
|
||||
last = '4';
|
||||
}
|
||||
uart_put_byte(&UART_DROP_PORT, last);
|
||||
uart_put_byte(&UART_DROP_PORT, 0, last);
|
||||
}
|
||||
|
||||
@@ -61,10 +61,10 @@ extern mavlink_system_t mavlink_system;
|
||||
* The MAVLink link description
|
||||
*/
|
||||
#define MAVLinkDev (&(MAVLINK_DEV).device)
|
||||
#define MAVLinkTransmit(c) MAVLinkDev->put_byte(MAVLinkDev->periph, c)
|
||||
#define MAVLinkTransmit(c) MAVLinkDev->put_byte(MAVLinkDev->periph, 0, c)
|
||||
#define MAVLinkChAvailable() MAVLinkDev->char_available(MAVLinkDev->periph)
|
||||
#define MAVLinkGetch() MAVLinkDev->get_byte(MAVLinkDev->periph)
|
||||
#define MAVLinkSendMessage() MAVLinkDev->send_message(MAVLinkDev->periph)
|
||||
#define MAVLinkSendMessage() MAVLinkDev->send_message(MAVLinkDev->periph, 0)
|
||||
|
||||
/**
|
||||
* Module functions
|
||||
|
||||
@@ -47,7 +47,7 @@
|
||||
|
||||
|
||||
#define CameraLinkDev (&((CAMERA_LINK).device))
|
||||
#define CameraLinkTransmit(c) CameraLinkDev->put_byte(CameraLinkDev->periph, c)
|
||||
#define CameraLinkTransmit(c) CameraLinkDev->put_byte(CameraLinkDev->periph, 0, c)
|
||||
#define CameraLinkChAvailable() CameraLinkDev->char_available(CameraLinkDev->periph)
|
||||
#define CameraLinkGetch() CameraLinkDev->get_byte(CameraLinkDev->periph)
|
||||
|
||||
|
||||
@@ -56,20 +56,38 @@ uint16_t gps_ubx_i2c_bytes_to_read; ///< ublox bytes to read
|
||||
* @param p unused
|
||||
*/
|
||||
void null_function(struct GpsUbxI2C *p);
|
||||
|
||||
/** Check available space in transmit buffer
|
||||
* @param p unused
|
||||
* @param fd unused
|
||||
* @param len number of bytes to check
|
||||
*/
|
||||
int gps_i2c_check_free_space(struct GpsUbxI2C *p, long *fd, uint16_t len);
|
||||
|
||||
/** Put byte into transmit buffer.
|
||||
* @param p unused
|
||||
* @param fd unused
|
||||
* @param data byte to put in buffer
|
||||
*/
|
||||
void gps_i2c_put_byte(struct GpsUbxI2C *p, uint8_t data);
|
||||
void gps_i2c_put_byte(struct GpsUbxI2C *p, long fd, uint8_t data);
|
||||
|
||||
/** Put bytes into transmit buffer.
|
||||
* @param p unused
|
||||
* @param fd unused
|
||||
* @param data byte to put in buffer
|
||||
*/
|
||||
void gps_i2c_put_buffer(struct GpsUbxI2C *p, long fd, uint8_t *data, uint16_t len);
|
||||
|
||||
/** send buffer when ready
|
||||
* @param p unused
|
||||
*/
|
||||
void gps_i2c_msg_ready(struct GpsUbxI2C *p);
|
||||
void gps_i2c_msg_ready(struct GpsUbxI2C *p, long fd);
|
||||
|
||||
/** check if a new character is available
|
||||
* @param p unused
|
||||
*/
|
||||
uint8_t gps_i2c_char_available(struct GpsUbxI2C *p);
|
||||
|
||||
/** get a new char
|
||||
* @param p unused
|
||||
*/
|
||||
@@ -88,22 +106,36 @@ void gps_ubx_i2c_init(void)
|
||||
gps_i2c.tx_rdy = TRUE;
|
||||
|
||||
gps_i2c.device.periph = (void *)&gps_i2c;
|
||||
gps_i2c.device.check_free_space = (check_free_space_t)null_function; ///< check if transmit buffer is not full
|
||||
gps_i2c.device.put_byte = (put_byte_t)gps_i2c_put_byte; ///< put one byte
|
||||
gps_i2c.device.send_message = (send_message_t)gps_i2c_msg_ready; ///< send completed buffer
|
||||
gps_i2c.device.char_available = (char_available_t)gps_i2c_char_available; ///< check if a new character is available
|
||||
gps_i2c.device.get_byte = (get_byte_t)gps_i2c_getch; ///< get a new char
|
||||
gps_i2c.device.set_baudrate = (set_baudrate_t)null_function; ///< set device baudrate
|
||||
gps_i2c.device.check_free_space = (check_free_space_t)gps_i2c_check_free_space; ///< check if transmit buffer is not full
|
||||
gps_i2c.device.put_byte = (put_byte_t)gps_i2c_put_byte; ///< put one byte
|
||||
gps_i2c.device.put_buffer = (put_buffer_t)gps_i2c_put_buffer; ///< put several bytes
|
||||
gps_i2c.device.send_message = (send_message_t)gps_i2c_msg_ready; ///< send completed buffer
|
||||
gps_i2c.device.char_available = (char_available_t)gps_i2c_char_available; ///< check if a new character is available
|
||||
gps_i2c.device.get_byte = (get_byte_t)gps_i2c_getch; ///< get a new char
|
||||
gps_i2c.device.set_baudrate = (set_baudrate_t)null_function; ///< set device baudrate
|
||||
}
|
||||
|
||||
void null_function(struct GpsUbxI2C *p __attribute__((unused))) {}
|
||||
|
||||
void gps_i2c_put_byte(struct GpsUbxI2C *p __attribute__((unused)), uint8_t data)
|
||||
int gps_i2c_check_free_space(struct GpsUbxI2C *p __attribute__((unused)), long *fd __attribute__((unused)), uint16_t len)
|
||||
{
|
||||
return (GPS_I2C_BUF_SIZE - gps_i2c.tx_buf_idx) >= len;
|
||||
}
|
||||
|
||||
void gps_i2c_put_buffer(struct GpsUbxI2C *p, long fd, uint8_t *data, uint16_t len)
|
||||
{
|
||||
int i = 0;
|
||||
for (i = 0; i < len; i++) {
|
||||
gps_i2c_put_byte(p, fd, data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void gps_i2c_put_byte(struct GpsUbxI2C *p __attribute__((unused)), long fd __attribute__((unused)), uint8_t data)
|
||||
{
|
||||
gps_i2c.tx_buf[gps_i2c.tx_buf_idx++] = data;
|
||||
}
|
||||
|
||||
void gps_i2c_msg_ready(struct GpsUbxI2C *p __attribute__((unused)))
|
||||
void gps_i2c_msg_ready(struct GpsUbxI2C *p __attribute__((unused)), long fd __attribute__((unused)))
|
||||
{
|
||||
gps_i2c.write_state = gps_i2c_write_cfg;
|
||||
gps_i2c.tx_rdy = FALSE;
|
||||
|
||||
@@ -73,7 +73,7 @@ Receiving:
|
||||
#define GSMLinkDev (&(GSM_LINK).device)
|
||||
|
||||
#define GSMLinkChAvailable() GSMLinkDev->check_available(GSMLinkDev->periph)
|
||||
#define GSMLinkTransmit(_c) GSMLinkDev->put_byte(GSMLinkDev->periph, _c)
|
||||
#define GSMLinkTransmit(_c) GSMLinkDev->put_byte(GSMLinkDev->periph, 0, _c)
|
||||
#define GSMLinkGetch() GSMLinkDev->get_byte(GSMLinkDev->periph)
|
||||
#define ReadGSMBuffer() { while (GSMLinkChAvailable&&!gsm_line_received) gsm_parse(GSMLinkGetch()); }
|
||||
|
||||
|
||||
@@ -187,9 +187,9 @@ static void hott_send_telemetry_data(void)
|
||||
--hott_msg_len;
|
||||
if (hott_msg_len != 0) {
|
||||
msg_crc += *hott_msg_ptr;
|
||||
uart_put_byte(&HOTT_PORT, *hott_msg_ptr++);
|
||||
uart_put_byte(&HOTT_PORT, 0, *hott_msg_ptr++);
|
||||
} else {
|
||||
uart_put_byte(&HOTT_PORT, (int8_t)msg_crc);
|
||||
uart_put_byte(&HOTT_PORT, 0, (int8_t)msg_crc);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -79,7 +79,7 @@ void parse_ins_buffer(uint8_t);
|
||||
#include "mcu_periph/uart.h"
|
||||
#include "mcu_periph/spi.h"
|
||||
|
||||
#define InsSend1(c) InsLinkDevice->put_byte(InsLinkDevice->periph, c)
|
||||
#define InsSend1(c) InsLinkDevice->put_byte(InsLinkDevice->periph, 0, c)
|
||||
#define InsUartSend1(c) InsSend1(c)
|
||||
#define InsSend(_dat,_len) { for (uint8_t i = 0; i< (_len); i++) InsSend1(_dat[i]); };
|
||||
#define InsUartSetBaudrate(_b) uart_periph_set_baudrate(INS_LINK, _b)
|
||||
|
||||
@@ -159,7 +159,7 @@ void direct_memory_logger_periodic(void)
|
||||
}
|
||||
|
||||
for (i = 5; i < end_idx; i++) {
|
||||
uart_put_byte(&DM_LOG_UART, dml.buffer[i]);
|
||||
uart_put_byte(&DM_LOG_UART, 0, dml.buffer[i]);
|
||||
}
|
||||
|
||||
// Read next bytes
|
||||
|
||||
@@ -740,10 +740,11 @@ void send_buffer_to_uart(void)
|
||||
|
||||
uint8_t msg_size = memory_transaction.input_length;
|
||||
static uint8_t i = MEMORY_READ_LATTENCY;
|
||||
long fd = 0;
|
||||
|
||||
if (sending_buffer_to_uart) {
|
||||
|
||||
while (uart_check_free_space(&HS_LOG_UART, 1)) {
|
||||
while (uart_check_free_space(&HS_LOG_UART, &fd, 1)) {
|
||||
|
||||
if (i >= msg_size) {
|
||||
|
||||
@@ -756,7 +757,7 @@ void send_buffer_to_uart(void)
|
||||
}
|
||||
break;
|
||||
}
|
||||
uart_put_byte(&HS_LOG_UART, uart_read_buff[i]);
|
||||
uart_put_byte(&HS_LOG_UART, fd, uart_read_buff[i]);
|
||||
i++;
|
||||
}
|
||||
|
||||
|
||||
@@ -90,6 +90,7 @@ void sdlogger_spi_direct_init(void)
|
||||
/* Set function pointers in link_device to the logger functions */
|
||||
sdlogger_spi.device.check_free_space = (check_free_space_t)sdlogger_spi_direct_check_free_space;
|
||||
sdlogger_spi.device.put_byte = (put_byte_t)sdlogger_spi_direct_put_byte;
|
||||
sdlogger_spi.device.put_buffer = (put_buffer_t)sdlogger_spi_direct_put_buffer;
|
||||
sdlogger_spi.device.send_message = (send_message_t)sdlogger_spi_direct_send_message;
|
||||
sdlogger_spi.device.char_available = (char_available_t)sdlogger_spi_direct_char_available;
|
||||
sdlogger_spi.device.get_byte = (get_byte_t)sdlogger_spi_direct_get_byte;
|
||||
@@ -177,8 +178,9 @@ void sdlogger_spi_direct_periodic(void)
|
||||
if (sdcard1.status == SDCard_Idle) {
|
||||
/* Put bytes to the buffer until all is written or buffer is full */
|
||||
for (uint16_t i = sdlogger_spi.sdcard_buf_idx; i < SD_BLOCK_SIZE; i++) {
|
||||
if(uart_check_free_space(&(DOWNLINK_DEVICE), 1)) {
|
||||
uart_put_byte(&(DOWNLINK_DEVICE), sdcard1.input_buf[i]);
|
||||
long fd = 0;
|
||||
if (uart_check_free_space(&(DOWNLINK_DEVICE), &fd, 1)) {
|
||||
uart_put_byte(&(DOWNLINK_DEVICE), fd, sdcard1.input_buf[i]);
|
||||
}
|
||||
else {
|
||||
/* No free space left, abort for-loop */
|
||||
@@ -344,7 +346,7 @@ void sdlogger_spi_direct_command(void)
|
||||
sdlogger_spi.command = 0;
|
||||
}
|
||||
|
||||
bool sdlogger_spi_direct_check_free_space(struct sdlogger_spi_periph *p, uint8_t len)
|
||||
bool sdlogger_spi_direct_check_free_space(struct sdlogger_spi_periph *p, long *fd __attribute__((unused)), uint16_t len)
|
||||
{
|
||||
if (p->status == SDLogger_Logging) {
|
||||
/* Calculating free space in both buffers */
|
||||
@@ -355,7 +357,7 @@ bool sdlogger_spi_direct_check_free_space(struct sdlogger_spi_periph *p, uint8_t
|
||||
return false;
|
||||
}
|
||||
|
||||
void sdlogger_spi_direct_put_byte(struct sdlogger_spi_periph *p, uint8_t data)
|
||||
void sdlogger_spi_direct_put_byte(struct sdlogger_spi_periph *p, long fd __attribute__((unused)), uint8_t data)
|
||||
{
|
||||
/* SD Buffer full, write in logger buffer */
|
||||
if (p->sdcard_buf_idx > 512) {
|
||||
@@ -375,7 +377,15 @@ void sdlogger_spi_direct_put_byte(struct sdlogger_spi_periph *p, uint8_t data)
|
||||
}
|
||||
}
|
||||
|
||||
void sdlogger_spi_direct_send_message(void *p)
|
||||
void sdlogger_spi_direct_put_buffer(struct sdlogger_spi_periph *p, long fd, uint8_t *data, uint16_t len)
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < len; i++) {
|
||||
sdlogger_spi_direct_put_byte(p, fd, data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void sdlogger_spi_direct_send_message(void *p, long fd __attribute__((unused)))
|
||||
{
|
||||
(void) p;
|
||||
}
|
||||
|
||||
@@ -72,9 +72,10 @@ extern void sdlogger_spi_direct_index_received(void);
|
||||
extern void sdlogger_spi_direct_multiwrite_written(void);
|
||||
extern void sdlogger_spi_direct_command(void);
|
||||
|
||||
extern bool sdlogger_spi_direct_check_free_space(struct sdlogger_spi_periph *p, uint8_t len);
|
||||
extern void sdlogger_spi_direct_put_byte(struct sdlogger_spi_periph *p, uint8_t data);
|
||||
extern void sdlogger_spi_direct_send_message(void *p);
|
||||
extern bool sdlogger_spi_direct_check_free_space(struct sdlogger_spi_periph *p, long *fd, uint16_t len);
|
||||
extern void sdlogger_spi_direct_put_byte(struct sdlogger_spi_periph *p, long fd, uint8_t data);
|
||||
extern void sdlogger_spi_direct_put_buffer(struct sdlogger_spi_periph *p, long fd, uint8_t data, uint16_t len);
|
||||
extern void sdlogger_spi_direct_send_message(void *p, long fd);
|
||||
extern int sdlogger_spi_direct_char_available(void *p);
|
||||
extern uint8_t sdlogger_spi_direct_get_byte(void *p);
|
||||
|
||||
|
||||
@@ -42,7 +42,7 @@
|
||||
#define MetBuffer() MetLinkDevice->char_available(MetLinkDevice->periph)
|
||||
#define MetGetch() MetLinkDevice->get_byte(MetLinkDevice->periph)
|
||||
#define ReadMetBuffer() { while (MetBuffer()&&!met_msg_received) parse_met_buffer(MetGetch()); }
|
||||
#define MetSend1(c) MetLinkDevice->put_byte(MetLinkDevice->periph, c)
|
||||
#define MetSend1(c) MetLinkDevice->put_byte(MetLinkDevice->periph, 0, c)
|
||||
#define MetUartSend1(c) MetSend1(c)
|
||||
#define MetSend(_dat,_len) { for (uint8_t i = 0; i< (_len); i++) MetSend1(_dat[i]); };
|
||||
#define MetUartSetBaudrate(_b) uart_periph_set_baudrate(&(MET_LINK), _b)
|
||||
|
||||
@@ -41,7 +41,7 @@ PRINT_CONFIG_VAR(STEREO_UART)
|
||||
struct link_device *xdev = STEREO_PORT;
|
||||
|
||||
#define StereoGetch() STEREO_PORT ->get_byte(STEREO_PORT->periph)
|
||||
#define StereoSend1(c) STEREO_PORT->put_byte(STEREO_PORT->periph, c)
|
||||
#define StereoSend1(c) STEREO_PORT->put_byte(STEREO_PORT->periph, 0, c)
|
||||
#define StereoUartSend1(c) StereoSend1(c)
|
||||
#define StereoSend(_dat,_len) { for (uint8_t i = 0; i< (_len); i++) StereoSend1(_dat[i]); };
|
||||
#define StereoUartSetBaudrate(_b) uart_periph_set_baudrate(STEREO_PORT, _b);
|
||||
|
||||
@@ -76,9 +76,10 @@ uint8_t stereoprot_isStartOfMsg(uint8_t *stack, uint16_t i, uint16_t buffer_size
|
||||
|
||||
void WritePart(struct link_device *dev, uint8_t *code, uint8_t length)
|
||||
{
|
||||
if (dev->check_free_space(dev->periph, length)) {
|
||||
long fd = 0;
|
||||
if (dev->check_free_space(dev->periph, &fd, length)) {
|
||||
for (uint8_t index = 0; index < length; index++) {
|
||||
dev->put_byte(dev->periph, code[index]);
|
||||
dev->put_byte(dev->periph, fd, code[index]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -83,12 +83,12 @@ void actuators_spektrum_set(void)
|
||||
static inline void actuators_spektrum_send(struct link_device *dev)
|
||||
{
|
||||
uint8_t i = 0;
|
||||
dev->put_byte(dev->periph, 0x00); // number missed frames
|
||||
dev->put_byte(dev->periph, 0x12); // 7 channels, 11 bit, 11ms
|
||||
dev->put_byte(dev->periph, 0, 0x00); // number missed frames
|
||||
dev->put_byte(dev->periph, 0x12); // 7 channels, 11 bit, 0, 11ms
|
||||
|
||||
/* Transmit all channels */
|
||||
for (i = 0; i < ACTUATORS_SPEKTRUM_MAX_NB; i++) {
|
||||
dev->put_byte(dev->periph, i << 3 | actuators_spektrum.cmds[i] >> 8);
|
||||
dev->put_byte(dev->periph, actuators_spektrum.cmds[i] & 0xFF);
|
||||
dev->put_byte(dev->periph, 0, i << 3 | actuators_spektrum.cmds[i] >> 8);
|
||||
dev->put_byte(dev->periph, 0, actuators_spektrum.cmds[i] & 0xFF);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -77,11 +77,11 @@ void ahrs_gx3_align(void)
|
||||
ahrs_gx3.is_aligned = false;
|
||||
|
||||
//make the gyros zero, takes 10s (specified in Byte 4 and 5)
|
||||
uart_put_byte(&GX3_PORT, 0xcd);
|
||||
uart_put_byte(&GX3_PORT, 0xc1);
|
||||
uart_put_byte(&GX3_PORT, 0x29);
|
||||
uart_put_byte(&GX3_PORT, 0x27);
|
||||
uart_put_byte(&GX3_PORT, 0x10);
|
||||
uart_put_byte(&GX3_PORT, 0, 0xcd);
|
||||
uart_put_byte(&GX3_PORT, 0, 0xc1);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x29);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x27);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x10);
|
||||
|
||||
ahrs_gx3.is_aligned = true;
|
||||
}
|
||||
@@ -125,59 +125,59 @@ void imu_impl_init(void)
|
||||
/*
|
||||
// FOR NON-CONTINUOUS MODE UNCOMMENT THIS
|
||||
//4 byte command for non-Continous Mode so we can set the other settings
|
||||
uart_put_byte(&GX3_PORT, 0xc4);
|
||||
uart_put_byte(&GX3_PORT, 0xc1);
|
||||
uart_put_byte(&GX3_PORT, 0x29);
|
||||
uart_put_byte(&GX3_PORT, 0x00); // stop
|
||||
uart_put_byte(&GX3_PORT, 0, 0xc4);
|
||||
uart_put_byte(&GX3_PORT, 0, 0xc1);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x29);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00); // stop
|
||||
*/
|
||||
|
||||
//Sampling Settings (0xDB)
|
||||
uart_put_byte(&GX3_PORT, 0xdb); //set update speed
|
||||
uart_put_byte(&GX3_PORT, 0xa8);
|
||||
uart_put_byte(&GX3_PORT, 0xb9);
|
||||
uart_put_byte(&GX3_PORT, 0, 0xdb); //set update speed
|
||||
uart_put_byte(&GX3_PORT, 0, 0xa8);
|
||||
uart_put_byte(&GX3_PORT, 0, 0xb9);
|
||||
//set rate of IMU link, is 1000/IMU_DIV
|
||||
#define IMU_DIV1 0
|
||||
#define IMU_DIV2 2
|
||||
#define ACC_FILT_DIV 2
|
||||
#define MAG_FILT_DIV 30
|
||||
#ifdef GX3_SAVE_SETTINGS
|
||||
uart_put_byte(&GX3_PORT, 0x02);//set params and save them in non-volatile memory
|
||||
uart_put_byte(&GX3_PORT, 0, 0x02);//set params and save them in non-volatile memory
|
||||
#else
|
||||
uart_put_byte(&GX3_PORT, 0x02); //set and don't save
|
||||
uart_put_byte(&GX3_PORT, 0, 0x02); //set and don't save
|
||||
#endif
|
||||
uart_put_byte(&GX3_PORT, IMU_DIV1);
|
||||
uart_put_byte(&GX3_PORT, IMU_DIV2);
|
||||
uart_put_byte(&GX3_PORT, 0b00000000); //set options byte 8 - GOOD
|
||||
uart_put_byte(&GX3_PORT, 0b00000011); //set options byte 7 - GOOD
|
||||
uart_put_byte(&GX3_PORT, 0, IMU_DIV1);
|
||||
uart_put_byte(&GX3_PORT, 0, IMU_DIV2);
|
||||
uart_put_byte(&GX3_PORT, 0, 0b00000000); //set options byte 8 - GOOD
|
||||
uart_put_byte(&GX3_PORT, 0, 0b00000011); //set options byte 7 - GOOD
|
||||
//0 - calculate orientation, 1 - enable coning & sculling, 2-3 reserved, 4 - no little endian data,
|
||||
// 5 - no NaN supressed, 6 - disable finite size correction, 7 - reserved,
|
||||
// 8 - enable magnetometer, 9 - reserved, 10 - enable magnetic north compensation, 11 - enable gravity compensation
|
||||
// 12 - no quaternion calculation, 13-15 reserved
|
||||
uart_put_byte(&GX3_PORT, ACC_FILT_DIV);
|
||||
uart_put_byte(&GX3_PORT, MAG_FILT_DIV); //mag window filter size == 33hz
|
||||
uart_put_byte(&GX3_PORT, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 10); // Up Compensation in secs, def=10s
|
||||
uart_put_byte(&GX3_PORT, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 10); // North Compensation in secs
|
||||
uart_put_byte(&GX3_PORT, 0x00); //power setting = 0, high power/bw
|
||||
uart_put_byte(&GX3_PORT, 0x00); //rest of the bytes are 0
|
||||
uart_put_byte(&GX3_PORT, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0, ACC_FILT_DIV);
|
||||
uart_put_byte(&GX3_PORT, 0, MAG_FILT_DIV); //mag window filter size == 33hz
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 10); // Up Compensation in secs, 0, def=10s
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0, 10); // North Compensation in secs
|
||||
uart_put_byte(&GX3_PORT, 0x00); //power setting = 0, 0, high power/bw
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00); //rest of the bytes are 0
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00);
|
||||
|
||||
// OPTIONAL: realign up and north
|
||||
/*
|
||||
uart_put_byte(&GX3_PORT, 0xdd);
|
||||
uart_put_byte(&GX3_PORT, 0x54);
|
||||
uart_put_byte(&GX3_PORT, 0x4c);
|
||||
uart_put_byte(&GX3_PORT, 3);
|
||||
uart_put_byte(&GX3_PORT, 10);
|
||||
uart_put_byte(&GX3_PORT, 10);
|
||||
uart_put_byte(&GX3_PORT, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0, 0xdd);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x54);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x4c);
|
||||
uart_put_byte(&GX3_PORT, 0, 3);
|
||||
uart_put_byte(&GX3_PORT, 0, 10);
|
||||
uart_put_byte(&GX3_PORT, 0, 10);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x00);
|
||||
*/
|
||||
|
||||
//Another wait loop for proper GX3 init
|
||||
@@ -187,23 +187,23 @@ void imu_impl_init(void)
|
||||
|
||||
#ifdef GX3_SET_WAKEUP_MODE
|
||||
//Mode Preset (0xD5)
|
||||
uart_put_byte(&GX3_PORT, 0xD5);
|
||||
uart_put_byte(&GX3_PORT, 0xBA);
|
||||
uart_put_byte(&GX3_PORT, 0x89);
|
||||
uart_put_byte(&GX3_PORT, 0x02); // wake up in continuous mode
|
||||
uart_put_byte(&GX3_PORT, 0, 0xD5);
|
||||
uart_put_byte(&GX3_PORT, 0, 0xBA);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x89);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x02); // wake up in continuous mode
|
||||
|
||||
//Continuous preset (0xD6)
|
||||
uart_put_byte(&GX3_PORT, 0xD6);
|
||||
uart_put_byte(&GX3_PORT, 0xC6);
|
||||
uart_put_byte(&GX3_PORT, 0x6B);
|
||||
uart_put_byte(&GX3_PORT, 0xc8); // accel, gyro, R
|
||||
uart_put_byte(&GX3_PORT, 0, 0xD6);
|
||||
uart_put_byte(&GX3_PORT, 0, 0xC6);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x6B);
|
||||
uart_put_byte(&GX3_PORT, 0xc8); // accel, gyro, 0, R
|
||||
#endif
|
||||
|
||||
//4 byte command for Continous Mode
|
||||
uart_put_byte(&GX3_PORT, 0xc4);
|
||||
uart_put_byte(&GX3_PORT, 0xc1);
|
||||
uart_put_byte(&GX3_PORT, 0x29);
|
||||
uart_put_byte(&GX3_PORT, 0xc8); // accel,gyro,R
|
||||
uart_put_byte(&GX3_PORT, 0, 0xc4);
|
||||
uart_put_byte(&GX3_PORT, 0, 0xc1);
|
||||
uart_put_byte(&GX3_PORT, 0, 0x29);
|
||||
uart_put_byte(&GX3_PORT, 0xc8); // accel,gyro, 0,R
|
||||
|
||||
// Reset gyros to zero
|
||||
ahrs_gx3_align();
|
||||
@@ -218,7 +218,7 @@ void imu_impl_init(void)
|
||||
void imu_periodic(void)
|
||||
{
|
||||
/* IF IN NON-CONTINUOUS MODE, REQUEST DATA NOW
|
||||
uart_put_byte(&GX3_PORT, 0xc8); // accel,gyro,R
|
||||
uart_put_byte(&GX3_PORT, 0xc8); // accel,gyro, 0,R
|
||||
*/
|
||||
}
|
||||
|
||||
|
||||
@@ -64,17 +64,22 @@ static void launchBatterySurveyThread (void)
|
||||
}
|
||||
|
||||
// Functions for the generic device API
|
||||
static int sdlog_check_free_space(struct chibios_sdlog* p __attribute__((unused)), uint8_t len __attribute__((unused)))
|
||||
static int sdlog_check_free_space(struct chibios_sdlog* p __attribute__((unused)), long *fd __attribute__((unused)), uint16_t len __attribute__((unused)))
|
||||
{
|
||||
return true;
|
||||
return 1;
|
||||
}
|
||||
|
||||
static void sdlog_transmit(struct chibios_sdlog* p, uint8_t byte)
|
||||
static void sdlog_transmit(struct chibios_sdlog* p, long fd __attribute__((unused)), uint8_t byte)
|
||||
{
|
||||
sdLogWriteByte(*p->file, byte);
|
||||
}
|
||||
|
||||
static void sdlog_send(struct chibios_sdlog* p __attribute__((unused))) { }
|
||||
static void sdlog_transmit_buffer(struct chibios_sdlog* p, long fd __attribute__((unused)), uint8_t *data, uint16_t len)
|
||||
{
|
||||
sdLogWriteRaw(*p->file, data, len);
|
||||
}
|
||||
|
||||
static void sdlog_send(struct chibios_sdlog* p __attribute__((unused)), long fd __attribute__((unused))) { }
|
||||
|
||||
static int null_function(struct chibios_sdlog *p __attribute__((unused))) { return 0; }
|
||||
|
||||
@@ -86,6 +91,7 @@ void chibios_sdlog_init(struct chibios_sdlog *sdlog, FileDes *file)
|
||||
sdlog->device.periph = (void *)(sdlog);
|
||||
sdlog->device.check_free_space = (check_free_space_t) sdlog_check_free_space;
|
||||
sdlog->device.put_byte = (put_byte_t) sdlog_transmit;
|
||||
sdlog->device.put_buffer = (put_buffer_t) sdlog_transmit_buffer;
|
||||
sdlog->device.send_message = (send_message_t) sdlog_send;
|
||||
sdlog->device.char_available = (char_available_t) null_function; // write only
|
||||
sdlog->device.get_byte = (get_byte_t) null_function; // write only
|
||||
|
||||
@@ -72,7 +72,7 @@ void bluegiga_transmit(struct bluegiga_periph *p, uint8_t data);
|
||||
void bluegiga_receive(struct spi_transaction *trans);
|
||||
|
||||
// Functions for the generic link device device API
|
||||
static int dev_check_free_space(struct bluegiga_periph *p, uint8_t len)
|
||||
static int dev_check_free_space(struct bluegiga_periph *p, long *fd __attribute__((unused)), uint16_t len)
|
||||
{
|
||||
// check if there is enough space for message
|
||||
// NB if BLUEGIGA_BUFFER_SIZE is smaller than 256 then an additional check is needed that len < BLUEGIGA_BUFFER_SIZE
|
||||
@@ -82,11 +82,18 @@ static int dev_check_free_space(struct bluegiga_periph *p, uint8_t len)
|
||||
|
||||
return false;
|
||||
}
|
||||
static void dev_put_byte(struct bluegiga_periph *p, uint8_t byte)
|
||||
static void dev_put_buffer(struct bluegiga_periph *p, long fd __attribute__((unused)), uint8_t *data, uint16_t len)
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < len; i++) {
|
||||
bluegiga_transmit(p, data[i]);
|
||||
}
|
||||
}
|
||||
static void dev_put_byte(struct bluegiga_periph *p, long fd __attribute__((unused)), uint8_t byte)
|
||||
{
|
||||
bluegiga_transmit(p, byte);
|
||||
}
|
||||
static void dev_send_message(struct bluegiga_periph *p)
|
||||
static void dev_send_message(struct bluegiga_periph *p, long fd __attribute__((unused)))
|
||||
{
|
||||
p->end_of_msg = p->tx_insert_idx;
|
||||
}
|
||||
@@ -163,6 +170,7 @@ void bluegiga_init(struct bluegiga_periph *p)
|
||||
p->device.periph = (void *)(p);
|
||||
p->device.check_free_space = (check_free_space_t) dev_check_free_space;
|
||||
p->device.put_byte = (put_byte_t) dev_put_byte;
|
||||
p->device.put_buffer = (put_buffer_t) dev_put_buffer;
|
||||
p->device.send_message = (send_message_t) dev_send_message;
|
||||
p->device.char_available = (char_available_t) dev_char_available;
|
||||
p->device.get_byte = (get_byte_t) dev_get_byte;
|
||||
@@ -199,7 +207,8 @@ void bluegiga_init(struct bluegiga_periph *p)
|
||||
/* Add one byte to the end of tx circular buffer */
|
||||
void bluegiga_transmit(struct bluegiga_periph *p, uint8_t data)
|
||||
{
|
||||
if (dev_check_free_space(p, 1) && coms_status != BLUEGIGA_UNINIT) {
|
||||
long fd = 0;
|
||||
if (dev_check_free_space(p, &fd, 1) && coms_status != BLUEGIGA_UNINIT) {
|
||||
p->tx_buf[p->tx_insert_idx] = data;
|
||||
bluegiga_increment_buf(&p->tx_insert_idx, 1);
|
||||
}
|
||||
|
||||
@@ -201,7 +201,7 @@ static void send_superbit(struct transport_tx *trans, struct link_device *dev)
|
||||
#endif
|
||||
|
||||
// Functions for the generic device API
|
||||
static bool superbitrf_check_free_space(struct SuperbitRF *p, uint8_t len)
|
||||
static bool superbitrf_check_free_space(struct SuperbitRF *p, long *fd __attribute__((unused)), uint16_t len)
|
||||
{
|
||||
int16_t space = p->tx_extract_idx - p->tx_insert_idx;
|
||||
if (space <= 0) {
|
||||
@@ -210,13 +210,21 @@ static bool superbitrf_check_free_space(struct SuperbitRF *p, uint8_t len)
|
||||
return (uint16_t)(space - 1) >= len;
|
||||
}
|
||||
|
||||
static void superbitrf_transmit(struct SuperbitRF *p, uint8_t byte)
|
||||
static void superbitrf_transmit(struct SuperbitRF *p, long fd __attribute__((unused)), uint8_t byte)
|
||||
{
|
||||
p->tx_buffer[p->tx_insert_idx] = byte;
|
||||
p->tx_insert_idx = (p->tx_insert_idx + 1) % SUPERBITRF_TX_BUFFER_SIZE;
|
||||
}
|
||||
|
||||
static void superbitrf_send(struct SuperbitRF *p __attribute__((unused))) { }
|
||||
static void superbitrf_transmit_buffer(struct SuperbitRF *p, long fd, uint8_t *data, uint16_t len)
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < len; i++) {
|
||||
superbitrf_transmit(p, fd, data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
static void superbitrf_send(struct SuperbitRF *p __attribute__((unused)), long fd __attribute__((unused))) { }
|
||||
|
||||
static int null_function(struct SuperbitRF *p __attribute__((unused))) { return 0; }
|
||||
|
||||
@@ -244,6 +252,7 @@ void superbitrf_init(void)
|
||||
superbitrf.device.periph = (void *)(&superbitrf);
|
||||
superbitrf.device.check_free_space = (check_free_space_t) superbitrf_check_free_space;
|
||||
superbitrf.device.put_byte = (put_byte_t) superbitrf_transmit;
|
||||
superbitrf.device.put_buffer = (put_buffer_t) superbitrf_transmit_buffer;
|
||||
superbitrf.device.send_message = (send_message_t) superbitrf_send;
|
||||
superbitrf.device.char_available = (char_available_t) null_function; // not needed
|
||||
superbitrf.device.get_byte = (get_byte_t) null_function; // not needed
|
||||
|
||||
@@ -39,7 +39,7 @@ static inline void print_string(struct link_device *dev, char *s)
|
||||
{
|
||||
uint8_t i = 0;
|
||||
while (s[i]) {
|
||||
dev->put_byte(dev->periph, s[i]);
|
||||
dev->put_byte(dev->periph, 0, s[i]);
|
||||
i++;
|
||||
}
|
||||
}
|
||||
@@ -60,8 +60,8 @@ static inline void print_hex(struct link_device *dev, uint8_t c)
|
||||
'8', '9', 'A', 'B', 'C', 'D', 'E', 'F' };
|
||||
uint8_t high = (c & 0xF0)>>4;
|
||||
uint8_t low = c & 0x0F;
|
||||
dev->put_byte(dev->periph, hex[high]);
|
||||
dev->put_byte(dev->periph, hex[low]);
|
||||
dev->put_byte(dev->periph, 0, hex[high]);
|
||||
dev->put_byte(dev->periph, 0, hex[low]);
|
||||
}
|
||||
|
||||
#define _PrintHex16(out_fun, c ) { \
|
||||
|
||||
@@ -169,9 +169,10 @@ static inline uint16_t w5100_sock_get16(uint8_t _sock, uint16_t _reg)
|
||||
}
|
||||
|
||||
// Functions for the generic device API
|
||||
static int true_function(struct w5100_periph *p __attribute__((unused)), uint8_t len __attribute__((unused))) { return true; }
|
||||
static void dev_transmit(struct w5100_periph *p __attribute__((unused)), uint8_t byte) { w5100_transmit(byte); }
|
||||
static void dev_send(struct w5100_periph *p __attribute__((unused))) { w5100_send(); }
|
||||
static int true_function(struct w5100_periph *p __attribute__((unused)), long *fd __attribute__((unused)), uint16_t len __attribute__((unused))) { return true; }
|
||||
static void dev_transmit(struct w5100_periph *p __attribute__((unused)), long fd __attribute__((unused)), uint8_t byte) { w5100_transmit(byte); }
|
||||
static void dev_transmit_buffer(struct w5100_periph *p __attribute__((unused)), long fd __attribute__((unused)), uint8_t *data, uint16_t len) { w5100_transmit_buffer(data, len); }
|
||||
static void dev_send(struct w5100_periph *p __attribute__((unused)), long fd __attribute__((unused))) { w5100_send(); }
|
||||
static int dev_char_available(struct w5100_periph *p __attribute__((unused))) { return w5100_ch_available; }
|
||||
static uint8_t dev_getch(struct w5100_periph *p __attribute__((unused)))
|
||||
{
|
||||
@@ -252,6 +253,7 @@ void w5100_init(void)
|
||||
chip0.device.periph = (void *)(&chip0);
|
||||
chip0.device.check_free_space = (check_free_space_t) true_function;
|
||||
chip0.device.put_byte = (put_byte_t) dev_transmit;
|
||||
chip0.device.put_buffer = (put_buffer_t) dev_transmit_buffer;
|
||||
chip0.device.send_message = (send_message_t) dev_send;
|
||||
chip0.device.char_available = (char_available_t) dev_char_available;
|
||||
chip0.device.get_byte = (get_byte_t) dev_getch;
|
||||
@@ -272,6 +274,14 @@ void w5100_transmit(uint8_t data)
|
||||
chip0.tx_insert_idx[ chip0.curbuf ] = temp;
|
||||
}
|
||||
|
||||
void w5100_transmit_buffer(uint8_t *data, uint16_t len)
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < len; i++) {
|
||||
w5100_transmit(data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
void w5100_send()
|
||||
{
|
||||
// Now send off spi transaction.
|
||||
|
||||
@@ -66,6 +66,7 @@ extern struct w5100_periph chip0;
|
||||
|
||||
void w5100_init(void);
|
||||
void w5100_transmit(uint8_t data);
|
||||
void w5100_transmit_buffer(uint8_t *data, uint16_t len);
|
||||
uint16_t w5100_receive(uint8_t *buf, uint16_t len);
|
||||
void w5100_send(void);
|
||||
uint16_t w5100_rx_size(uint8_t _s);
|
||||
|
||||
@@ -71,11 +71,12 @@ void nmea_configure(void)
|
||||
for (i = furuno_cfg_cnt; i < GPS_FURUNO_SETTINGS_NB; i++) {
|
||||
len = strlen(gps_furuno_settings[i]);
|
||||
// Check if there is enough space to send the config msg
|
||||
if (GpsLinkDevice->check_free_space(GpsLinkDevice->periph, len + 6)) {
|
||||
long fd = 0;
|
||||
if (GpsLinkDevice->check_free_space(GpsLinkDevice->periph, &fd, len + 6)) {
|
||||
crc = nmea_calc_crc(gps_furuno_settings[i], len);
|
||||
sprintf(buf, "$%s*%02X\r\n", gps_furuno_settings[i], crc);
|
||||
for (j = 0; j < len + 6; j++) {
|
||||
GpsLinkDevice->put_byte(GpsLinkDevice->periph, buf[j]);
|
||||
GpsLinkDevice->put_byte(GpsLinkDevice->periph, fd, buf[j]);
|
||||
}
|
||||
furuno_cfg_cnt++;
|
||||
} else {
|
||||
|
||||
@@ -432,7 +432,7 @@ void gps_mtk_register(void)
|
||||
static void MtkSend_CFG(char *dat)
|
||||
{
|
||||
struct link_device *dev = &((MTK_GPS_LINK).device);
|
||||
while (*dat != 0) { dev->put_byte(dev->periph, *dat++); }
|
||||
while (*dat != 0) { dev->put_byte(dev->periph, 0, *dat++); }
|
||||
}
|
||||
|
||||
void gps_configure_uart(void)
|
||||
|
||||
@@ -397,7 +397,7 @@ uint32_t gps_piksi_write(uint8_t *buff, uint32_t n, void *context __attribute__(
|
||||
{
|
||||
uint32_t i = 0;
|
||||
for (i = 0; i < n; i++) {
|
||||
uart_put_byte(&(PIKSI_GPS_LINK), buff[i]);
|
||||
uart_put_byte(&(PIKSI_GPS_LINK), 0, buff[i]);
|
||||
}
|
||||
return n;
|
||||
}
|
||||
|
||||
@@ -280,15 +280,15 @@ restart:
|
||||
|
||||
static void ubx_send_1byte(struct link_device *dev, uint8_t byte)
|
||||
{
|
||||
dev->put_byte(dev->periph, byte);
|
||||
dev->put_byte(dev->periph, 0, byte);
|
||||
gps_ubx.send_ck_a += byte;
|
||||
gps_ubx.send_ck_b += gps_ubx.send_ck_a;
|
||||
}
|
||||
|
||||
void ubx_header(struct link_device *dev, uint8_t nav_id, uint8_t msg_id, uint16_t len)
|
||||
{
|
||||
dev->put_byte(dev->periph, UBX_SYNC1);
|
||||
dev->put_byte(dev->periph, UBX_SYNC2);
|
||||
dev->put_byte(dev->periph, 0, UBX_SYNC1);
|
||||
dev->put_byte(dev->periph, 0, UBX_SYNC2);
|
||||
gps_ubx.send_ck_a = 0;
|
||||
gps_ubx.send_ck_b = 0;
|
||||
ubx_send_1byte(dev, nav_id);
|
||||
@@ -299,9 +299,9 @@ void ubx_header(struct link_device *dev, uint8_t nav_id, uint8_t msg_id, uint16_
|
||||
|
||||
void ubx_trailer(struct link_device *dev)
|
||||
{
|
||||
dev->put_byte(dev->periph, gps_ubx.send_ck_a);
|
||||
dev->put_byte(dev->periph, gps_ubx.send_ck_b);
|
||||
dev->send_message(dev->periph);
|
||||
dev->put_byte(dev->periph, 0, gps_ubx.send_ck_a);
|
||||
dev->put_byte(dev->periph, 0, gps_ubx.send_ck_b);
|
||||
dev->send_message(dev->periph, 0);
|
||||
}
|
||||
|
||||
void ubx_send_bytes(struct link_device *dev, uint8_t len, uint8_t *bytes)
|
||||
|
||||
@@ -77,7 +77,7 @@ inline uint16_t UM6_calculate_checksum(uint8_t packet_buffer[], uint8_t packet_l
|
||||
inline void UM6_send_packet(uint8_t *packet_buffer, uint8_t packet_length)
|
||||
{
|
||||
for (int i = 0; i < packet_length; i++) {
|
||||
uart_put_byte(&(UM6_LINK), packet_buffer[i]);
|
||||
uart_put_byte(&(UM6_LINK), 0, packet_buffer[i]);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -199,11 +199,11 @@ static void checkPx4RebootCommand(unsigned char b)
|
||||
|
||||
//send some magic back
|
||||
//this is the same as the Pixhawk IO code would send
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0x00);
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0xe5);
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0x32);
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0x0a);
|
||||
intermcu_device->put_byte(intermcu_device->periph,
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0, 0x00);
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0, 0xe5);
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0, 0x32);
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0, 0x0a);
|
||||
intermcu_device->put_byte(intermcu_device->periph, 0,
|
||||
0x66); // dummy byte, seems to be necessary otherwise one byte is missing at the fmu side...
|
||||
|
||||
while (((struct uart_periph *)(intermcu_device->periph))->tx_running) {
|
||||
|
||||
@@ -63,10 +63,10 @@ static inline void main_event_task(void)
|
||||
mcu_event();
|
||||
|
||||
if (uart_char_available(&uart2)) {
|
||||
uart_put_byte(&uart1, uart_getch(&uart2));
|
||||
uart_put_byte(&uart1, 0, uart_getch(&uart2));
|
||||
}
|
||||
|
||||
if (uart_char_available(&uart1)) {
|
||||
uart_put_byte(&uart2, uart_getch(&uart1));
|
||||
uart_put_byte(&uart2, 0, uart_getch(&uart1));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -53,19 +53,19 @@ static inline void main_periodic(void)
|
||||
char ch;
|
||||
|
||||
#if USE_UART1
|
||||
uart_put_byte(&uart1, 'a');
|
||||
uart_put_byte(&uart1, 0, 'a');
|
||||
#endif
|
||||
#if USE_UART2
|
||||
uart_put_byte(&uart2, 'b');
|
||||
uart_put_byte(&uart2, 0, 'b');
|
||||
#endif
|
||||
#if USE_UART3
|
||||
uart_put_byte(&uart3, 'c');
|
||||
uart_put_byte(&uart3, 0, 'c');
|
||||
#endif
|
||||
#if USE_UART4
|
||||
uart_put_byte(&uart4, 'd');
|
||||
uart_put_byte(&uart4, 0, 'd');
|
||||
#endif
|
||||
#if USE_UART5
|
||||
uart_put_byte(&uart5, 'e');
|
||||
uart_put_byte(&uart5, 0, 'e');
|
||||
#endif
|
||||
|
||||
LED_OFF(1);
|
||||
|
||||
@@ -71,7 +71,7 @@ static inline void main_periodic(void)
|
||||
i = 0;
|
||||
}
|
||||
|
||||
uart_put_byte(&TEST_UART, foo[i]);
|
||||
uart_put_byte(&TEST_UART, 0, foo[i]);
|
||||
printf("%f, transmit: '%c'\n", get_sys_time_float(), foo[i]);
|
||||
|
||||
if (uart_char_available(&TEST_UART)) {
|
||||
|
||||
@@ -70,8 +70,8 @@ static inline void main_periodic(void)
|
||||
static uint8_t i = 0;
|
||||
|
||||
/* start "packet with zero */
|
||||
//uart_put_byte(&TEST_UART, 0);
|
||||
uart_put_byte(&TEST_UART, i);
|
||||
//uart_put_byte(&TEST_UART, 0, 0);
|
||||
uart_put_byte(&TEST_UART, 0, i);
|
||||
/* print status every x cycles */
|
||||
RunOnceEvery(1, printf("%f, transmit: '%d'\n", get_sys_time_float(), i););
|
||||
|
||||
|
||||
+1
-1
Submodule sw/ext/pprzlink updated: c323e3cce1...c8cefaf8ce
Reference in New Issue
Block a user