Skip to content

Commit

Permalink
[device] rename transmit with put_byte
Browse files Browse the repository at this point in the history
  • Loading branch information
gautierhattenberger committed Mar 22, 2015
1 parent e5216d6 commit 4aa23b0
Show file tree
Hide file tree
Showing 22 changed files with 41 additions and 41 deletions.
2 changes: 1 addition & 1 deletion sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c
Expand Up @@ -163,7 +163,7 @@ void spi_slave_hs_init(void)
// Configure generic device
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.transmit = (transmit_t) spi_slave_hs_transmit;
spi_slave_hs.device.put_byte = (put_byte_t) spi_slave_hs_transmit;
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;
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/arch/lpc21/usb_ser_hw.c
Expand Up @@ -618,7 +618,7 @@ void VCOM_init(void)
// Configure generic device
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.transmit = (transmit_t) usb_serial_transmit;
usb_serial.device.put_byte = (put_byte_t) usb_serial_transmit;
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;
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/arch/stm32/usb_ser_hw.c
Expand Up @@ -528,7 +528,7 @@ void VCOM_init(void)
// Configure generic device
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.transmit = (transmit_t) usb_serial_transmit;
usb_serial.device.put_byte = (put_byte_t) usb_serial_transmit;
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;
Expand Down
4 changes: 2 additions & 2 deletions sw/airborne/firmwares/fixedwing/fbw_datalink.c
Expand Up @@ -36,12 +36,12 @@

static inline void autopilot_parse(char c)
{
ModemLinkDevice->transmit(ModemLinkDevice->periph, c);
ModemLinkDevice->put_byte(ModemLinkDevice->periph, c);
}

static inline void modem_parse(char c)
{
AutopilotLinkDevice->transmit(AutopilotLinkDevice->periph, c);
AutopilotLinkDevice->put_byte(AutopilotLinkDevice->periph, c);
}

void fbw_datalink_periodic(void)
Expand Down
6 changes: 3 additions & 3 deletions sw/airborne/mcu_periph/link_device.h
Expand Up @@ -34,7 +34,7 @@
* to store in the device structure
*/
typedef int (*check_free_space_t)(void *, uint8_t);
typedef void (*transmit_t)(void *, uint8_t);
typedef void (*put_byte_t)(void *, uint8_t);
typedef void (*send_message_t)(void *);
typedef int (*char_available_t)(void *);
typedef uint8_t (*get_byte_t)(void *);
Expand All @@ -43,10 +43,10 @@ typedef uint8_t (*get_byte_t)(void *);
*/
struct link_device {
check_free_space_t check_free_space; ///< check if transmit buffer is not full
transmit_t transmit; ///< transmit one byte
put_byte_t put_byte; ///< put one byte
send_message_t send_message; ///< send completed buffer
char_available_t char_available; ///< check if a new character is available
get_byte_t get_byte; ///< get a new char
get_byte_t get_byte; ///< get a new char
void *periph; ///< pointer to parent implementation
};

Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/mcu_periph/uart.c
Expand Up @@ -201,7 +201,7 @@ void uart_periph_init(struct uart_periph *p)
p->fe_err = 0;
p->device.periph = (void *)p;
p->device.check_free_space = (check_free_space_t)uart_check_free_space;
p->device.transmit = (transmit_t)uart_transmit;
p->device.put_byte = (put_byte_t)uart_transmit;
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;
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/mcu_periph/udp.c
Expand Up @@ -62,7 +62,7 @@ void udp_periph_init(struct udp_periph *p, char *host, int port_out, int port_in
p->tx_insert_idx = 0;
p->device.periph = (void *)p;
p->device.check_free_space = (check_free_space_t) udp_check_free_space;
p->device.transmit = (transmit_t) udp_transmit;
p->device.put_byte = (put_byte_t) udp_transmit;
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;
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/modules/datalink/mavlink.h
Expand Up @@ -53,7 +53,7 @@ extern mavlink_system_t mavlink_system;
* The MAVLink link description
*/
#define MAVLinkDev (&(MAVLINK_DEV).device)
#define MAVLinkTransmit(c) MAVLinkDev->transmit(MAVLinkDev->periph, c)
#define MAVLinkTransmit(c) MAVLinkDev->put_byte(MAVLinkDev->periph, c)
#define MAVLinkChAvailable() MAVLinkDev->char_available(MAVLinkDev->periph)
#define MAVLinkGetch() MAVLinkDev->get_byte(MAVLinkDev->periph)
#define MAVLinkSendMessage() MAVLinkDev->send_message(MAVLinkDev->periph)
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/modules/digital_cam/uart_cam_ctrl.c
Expand Up @@ -46,7 +46,7 @@
#include "state.h"

#define CameraLinkDev (&(CAMERA_LINK).device)
#define CameraLinkTransmit(c) CameraLinkDev->transmit(CameraLinkDev->periph, c)
#define CameraLinkTransmit(c) CameraLinkDev->put_byte(CameraLinkDev->periph, c)
#define CameraLinkChAvailable() CameraLinkDev->check_available(CameraLinkDev->periph)
#define CameraLinkGetch() CameraLinkGetch->get_byte(CameraLinkDev->periph)

Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/modules/ins/ins_module.h
Expand Up @@ -79,7 +79,7 @@ void parse_ins_buffer(uint8_t);
#include "mcu_periph/uart.h"
#include "mcu_periph/spi.h"

#define InsSend1(c) InsLinkDevice->transmit(InsLinkDevice->periph, c)
#define InsSend1(c) InsLinkDevice->put_byte(InsLinkDevice->periph, 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)
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/modules/sensors/met_module.h
Expand Up @@ -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->transmit(MetLinkDevice->periph, c)
#define MetSend1(c) MetLinkDevice->put_byte(MetLinkDevice->periph, 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)
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c
Expand Up @@ -85,7 +85,7 @@ bool_t chibios_logInit(const bool_t binaryFile)
// Configure generic device
chibios_sdlog.device.periph = (void *)(&chibios_sdlog);
chibios_sdlog.device.check_free_space = (check_free_space_t) sdlog_check_free_space;
chibios_sdlog.device.transmit = (transmit_t) sdlog_transmit;
chibios_sdlog.device.put_byte = (put_byte_t) sdlog_transmit;
chibios_sdlog.device.send_message = (send_message_t) sdlog_send;
chibios_sdlog.device.char_available = (char_available_t) null_function; // write only
chibios_sdlog.device.get_byte = (get_byte_t) null_function; // write only
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/subsystems/datalink/ivy_transport.c
Expand Up @@ -196,7 +196,7 @@ void ivy_transport_init(void)
ivy_tp.trans_tx.count_bytes = (count_bytes_t) count_bytes;
ivy_tp.trans_tx.impl = (void *)(&ivy_tp);
ivy_tp.device.check_free_space = (check_free_space_t) check_free_space;
ivy_tp.device.transmit = (transmit_t) transmit;
ivy_tp.device.put_byte = (put_byte_t) transmit;
ivy_tp.device.send_message = (send_message_t) send_message;
ivy_tp.device.char_available = (char_available_t) null_function;
ivy_tp.device.get_byte = (get_byte_t) null_function;
Expand Down
10 changes: 5 additions & 5 deletions sw/airborne/subsystems/datalink/pprz_transport.c
Expand Up @@ -52,7 +52,7 @@ static void put_1byte(struct pprz_transport *trans, struct link_device *dev, con
{
trans->ck_a_tx += byte;
trans->ck_b_tx += trans->ck_a_tx;
dev->transmit(dev->periph, byte);
dev->put_byte(dev->periph, byte);
}

static void put_bytes(struct pprz_transport *trans, struct link_device *dev,
Expand Down Expand Up @@ -82,17 +82,17 @@ static uint8_t size_of(struct pprz_transport *trans __attribute__((unused)), uin
static void start_message(struct pprz_transport *trans, struct link_device *dev, uint8_t payload_len)
{
downlink.nb_msgs++;
dev->transmit(dev->periph, STX);
dev->put_byte(dev->periph, STX);
const uint8_t msg_len = size_of(trans, payload_len);
dev->transmit(dev->periph, msg_len);
dev->put_byte(dev->periph, msg_len);
trans->ck_a_tx = msg_len;
trans->ck_b_tx = msg_len;
}

static void end_message(struct pprz_transport *trans, struct link_device *dev)
{
dev->transmit(dev->periph, trans->ck_a_tx);
dev->transmit(dev->periph, trans->ck_b_tx);
dev->put_byte(dev->periph, trans->ck_a_tx);
dev->put_byte(dev->periph, trans->ck_b_tx);
dev->send_message(dev->periph);
}

Expand Down
6 changes: 3 additions & 3 deletions sw/airborne/subsystems/datalink/pprzlog_transport.c
Expand Up @@ -51,7 +51,7 @@ struct pprzlog_transport pprzlog_tp;
static void put_1byte(struct pprzlog_transport *trans, struct link_device *dev, const uint8_t byte)
{
trans->ck += byte;
dev->transmit(dev->periph, byte);
dev->put_byte(dev->periph, byte);
}

static void put_bytes(struct pprzlog_transport *trans, struct link_device *dev,
Expand Down Expand Up @@ -79,7 +79,7 @@ static uint8_t size_of(struct pprzlog_transport *trans __attribute__((unused)),

static void start_message(struct pprzlog_transport *trans, struct link_device *dev, uint8_t payload_len)
{
dev->transmit(dev->periph, STX_LOG);
dev->put_byte(dev->periph, STX_LOG);
const uint8_t msg_len = size_of(trans, payload_len);
trans->ck = 0;
put_1byte(trans, dev, msg_len);
Expand All @@ -90,7 +90,7 @@ static void start_message(struct pprzlog_transport *trans, struct link_device *d

static void end_message(struct pprzlog_transport *trans, struct link_device *dev)
{
dev->transmit(dev->periph, trans->ck);
dev->put_byte(dev->periph, trans->ck);
dev->send_message(dev->periph);
}

Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/subsystems/datalink/superbitrf.c
Expand Up @@ -243,7 +243,7 @@ void superbitrf_init(void)
// Configure generic device
superbitrf.device.periph = (void *)(&superbitrf);
superbitrf.device.check_free_space = (check_free_space_t) superbitrf_check_free_space;
superbitrf.device.transmit = (transmit_t) superbitrf_transmit;
superbitrf.device.put_byte = (put_byte_t) superbitrf_transmit;
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
Expand Down
6 changes: 3 additions & 3 deletions sw/airborne/subsystems/datalink/uart_print.h
Expand Up @@ -39,7 +39,7 @@ static inline void print_string(struct link_device *dev, char *s)
{
uint8_t i = 0;
while (s[i]) {
dev->transmit(dev->periph, s[i]);
dev->put_byte(dev->periph, s[i]);
i++;
}
}
Expand All @@ -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->transmit(dev->periph, hex[high]);
dev->transmit(dev->periph, hex[low]);
dev->put_byte(dev->periph, hex[high]);
dev->put_byte(dev->periph, hex[low]);
}

#define _PrintHex16(out_fun, c ) { \
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/subsystems/datalink/w5100.c
Expand Up @@ -251,7 +251,7 @@ void w5100_init(void)
// Configure generic device
chip0.device.periph = (void *)(&chip0);
chip0.device.check_free_space = (check_free_space_t) true_function;
chip0.device.transmit = (transmit_t) dev_transmit;
chip0.device.put_byte = (put_byte_t) dev_transmit;
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;
Expand Down
10 changes: 5 additions & 5 deletions sw/airborne/subsystems/datalink/xbee.c
Expand Up @@ -56,7 +56,7 @@ struct xbee_transport xbee_tp;
static void put_1byte(struct xbee_transport *trans, struct link_device *dev, const uint8_t byte)
{
trans->cs_tx += byte;
dev->transmit(dev->periph, byte);
dev->put_byte(dev->periph, byte);
}

static void put_bytes(struct xbee_transport *trans, struct link_device *dev,
Expand Down Expand Up @@ -86,10 +86,10 @@ static uint8_t size_of(struct xbee_transport *trans __attribute__((unused)), uin
static void start_message(struct xbee_transport *trans, struct link_device *dev, uint8_t payload_len)
{
downlink.nb_msgs++;
dev->transmit(dev->periph, XBEE_START);
dev->put_byte(dev->periph, XBEE_START);
const uint16_t len = payload_len + XBEE_API_OVERHEAD;
dev->transmit(dev->periph, (len >> 8));
dev->transmit(dev->periph, (len & 0xff));
dev->put_byte(dev->periph, (len >> 8));
dev->put_byte(dev->periph, (len & 0xff));
trans->cs_tx = 0;
const uint8_t header[] = XBEE_TX_HEADER;
put_bytes(trans, dev, DL_TYPE_UINT8, DL_FORMAT_SCALAR, XBEE_TX_OVERHEAD + 1, header);
Expand All @@ -98,7 +98,7 @@ static void start_message(struct xbee_transport *trans, struct link_device *dev,
static void end_message(struct xbee_transport *trans, struct link_device *dev)
{
trans->cs_tx = 0xff - trans->cs_tx;
dev->transmit(dev->periph, trans->cs_tx);
dev->put_byte(dev->periph, trans->cs_tx);
dev->send_message(dev->periph);
}

Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/subsystems/gps/gps_furuno.c
Expand Up @@ -68,7 +68,7 @@ void nmea_parse_prop_init(void)
// Check if there is enough space to send the config msg
if (GpsLinkDevice->check_free_space(GpsLinkDevice->periph, len + 6)) {
for (j = 0; j < len + 6; j++) {
GpsLinkDevice->transmit(GpsLinkDevice->periph, buf[j]);
GpsLinkDevice->put_byte(GpsLinkDevice->periph, buf[j]);
}
} else {
break;
Expand Down
2 changes: 1 addition & 1 deletion sw/airborne/subsystems/gps/gps_mtk.c
Expand Up @@ -422,7 +422,7 @@ void gps_mtk_parse(uint8_t c)
static void MtkSend_CFG(char *dat)
{
struct link_device *dev = &((GPS_LINK).device);
while (*dat != 0) { dev->transmit(dev->periph, *dat++); }
while (*dat != 0) { dev->put_byte(dev->periph, *dat++); }
}

void gps_configure_uart(void)
Expand Down
10 changes: 5 additions & 5 deletions sw/airborne/subsystems/gps/gps_ubx.c
Expand Up @@ -275,15 +275,15 @@ void gps_ubx_parse(uint8_t c)

static void ubx_send_1byte(struct link_device *dev, uint8_t byte)
{
dev->transmit(dev->periph, byte);
dev->put_byte(dev->periph, 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->transmit(dev->periph, UBX_SYNC1);
dev->transmit(dev->periph, UBX_SYNC2);
dev->put_byte(dev->periph, UBX_SYNC1);
dev->put_byte(dev->periph, UBX_SYNC2);
gps_ubx.send_ck_a = 0;
gps_ubx.send_ck_b = 0;
ubx_send_1byte(dev, nav_id);
Expand All @@ -294,8 +294,8 @@ void ubx_header(struct link_device *dev, uint8_t nav_id, uint8_t msg_id, uint16_

void ubx_trailer(struct link_device *dev)
{
dev->transmit(dev->periph, gps_ubx.send_ck_a);
dev->transmit(dev->periph, gps_ubx.send_ck_b);
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);
}

Expand Down

0 comments on commit 4aa23b0

Please sign in to comment.