diff --git a/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c b/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c index 53e58cdea3d..528a344ef8a 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c @@ -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; diff --git a/sw/airborne/arch/lpc21/usb_ser_hw.c b/sw/airborne/arch/lpc21/usb_ser_hw.c index 5923c144ef1..973db689846 100644 --- a/sw/airborne/arch/lpc21/usb_ser_hw.c +++ b/sw/airborne/arch/lpc21/usb_ser_hw.c @@ -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; diff --git a/sw/airborne/arch/stm32/usb_ser_hw.c b/sw/airborne/arch/stm32/usb_ser_hw.c index dd0e3eee599..b89a19bf8c8 100644 --- a/sw/airborne/arch/stm32/usb_ser_hw.c +++ b/sw/airborne/arch/stm32/usb_ser_hw.c @@ -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; diff --git a/sw/airborne/firmwares/fixedwing/fbw_datalink.c b/sw/airborne/firmwares/fixedwing/fbw_datalink.c index f99fef6ed9c..dfb5d6b7d09 100644 --- a/sw/airborne/firmwares/fixedwing/fbw_datalink.c +++ b/sw/airborne/firmwares/fixedwing/fbw_datalink.c @@ -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) diff --git a/sw/airborne/mcu_periph/link_device.h b/sw/airborne/mcu_periph/link_device.h index 2834ddc6c45..e282686d790 100644 --- a/sw/airborne/mcu_periph/link_device.h +++ b/sw/airborne/mcu_periph/link_device.h @@ -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 *); @@ -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 }; diff --git a/sw/airborne/mcu_periph/uart.c b/sw/airborne/mcu_periph/uart.c index 586399bf32e..7e1aa83750b 100644 --- a/sw/airborne/mcu_periph/uart.c +++ b/sw/airborne/mcu_periph/uart.c @@ -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; diff --git a/sw/airborne/mcu_periph/udp.c b/sw/airborne/mcu_periph/udp.c index 7256dccd5ac..d953a7de11a 100644 --- a/sw/airborne/mcu_periph/udp.c +++ b/sw/airborne/mcu_periph/udp.c @@ -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; diff --git a/sw/airborne/modules/datalink/mavlink.h b/sw/airborne/modules/datalink/mavlink.h index dd49a86627f..ac4c0145f3b 100644 --- a/sw/airborne/modules/datalink/mavlink.h +++ b/sw/airborne/modules/datalink/mavlink.h @@ -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) diff --git a/sw/airborne/modules/digital_cam/uart_cam_ctrl.c b/sw/airborne/modules/digital_cam/uart_cam_ctrl.c index 49f9aeefc2f..1d397f34c1e 100644 --- a/sw/airborne/modules/digital_cam/uart_cam_ctrl.c +++ b/sw/airborne/modules/digital_cam/uart_cam_ctrl.c @@ -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) diff --git a/sw/airborne/modules/ins/ins_module.h b/sw/airborne/modules/ins/ins_module.h index 584b204184c..3256e26626c 100644 --- a/sw/airborne/modules/ins/ins_module.h +++ b/sw/airborne/modules/ins/ins_module.h @@ -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) diff --git a/sw/airborne/modules/sensors/met_module.h b/sw/airborne/modules/sensors/met_module.h index aa31c3719b2..98dd0207872 100644 --- a/sw/airborne/modules/sensors/met_module.h +++ b/sw/airborne/modules/sensors/met_module.h @@ -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) diff --git a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c index 137d773bad3..da43b645ba7 100644 --- a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c +++ b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c @@ -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 diff --git a/sw/airborne/subsystems/datalink/ivy_transport.c b/sw/airborne/subsystems/datalink/ivy_transport.c index 81dd64daed5..93a66299dbe 100644 --- a/sw/airborne/subsystems/datalink/ivy_transport.c +++ b/sw/airborne/subsystems/datalink/ivy_transport.c @@ -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; diff --git a/sw/airborne/subsystems/datalink/pprz_transport.c b/sw/airborne/subsystems/datalink/pprz_transport.c index e995397c0b1..375cb63cbc2 100644 --- a/sw/airborne/subsystems/datalink/pprz_transport.c +++ b/sw/airborne/subsystems/datalink/pprz_transport.c @@ -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, @@ -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); } diff --git a/sw/airborne/subsystems/datalink/pprzlog_transport.c b/sw/airborne/subsystems/datalink/pprzlog_transport.c index 1fa3b170b37..0a47cdff2c5 100644 --- a/sw/airborne/subsystems/datalink/pprzlog_transport.c +++ b/sw/airborne/subsystems/datalink/pprzlog_transport.c @@ -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, @@ -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); @@ -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); } diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c index c26a25b0f85..eecdbfd1773 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -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 diff --git a/sw/airborne/subsystems/datalink/uart_print.h b/sw/airborne/subsystems/datalink/uart_print.h index 32bd9874337..97f16513dd0 100644 --- a/sw/airborne/subsystems/datalink/uart_print.h +++ b/sw/airborne/subsystems/datalink/uart_print.h @@ -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++; } } @@ -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 ) { \ diff --git a/sw/airborne/subsystems/datalink/w5100.c b/sw/airborne/subsystems/datalink/w5100.c index af11efe31ba..4b040e04885 100644 --- a/sw/airborne/subsystems/datalink/w5100.c +++ b/sw/airborne/subsystems/datalink/w5100.c @@ -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; diff --git a/sw/airborne/subsystems/datalink/xbee.c b/sw/airborne/subsystems/datalink/xbee.c index e80963ba80e..c23e8096951 100644 --- a/sw/airborne/subsystems/datalink/xbee.c +++ b/sw/airborne/subsystems/datalink/xbee.c @@ -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, @@ -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); @@ -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); } diff --git a/sw/airborne/subsystems/gps/gps_furuno.c b/sw/airborne/subsystems/gps/gps_furuno.c index efc28051a6c..c86275e69b1 100644 --- a/sw/airborne/subsystems/gps/gps_furuno.c +++ b/sw/airborne/subsystems/gps/gps_furuno.c @@ -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; diff --git a/sw/airborne/subsystems/gps/gps_mtk.c b/sw/airborne/subsystems/gps/gps_mtk.c index 5a61336b6bb..8591d8fd581 100644 --- a/sw/airborne/subsystems/gps/gps_mtk.c +++ b/sw/airborne/subsystems/gps/gps_mtk.c @@ -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) diff --git a/sw/airborne/subsystems/gps/gps_ubx.c b/sw/airborne/subsystems/gps/gps_ubx.c index af4bf06b62c..0a74c1cd367 100644 --- a/sw/airborne/subsystems/gps/gps_ubx.c +++ b/sw/airborne/subsystems/gps/gps_ubx.c @@ -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); @@ -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); }