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 7e46b28357..e0e3aa0d67 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 @@ -166,7 +166,7 @@ void spi_slave_hs_init(void) spi_slave_hs.device.transmit = (transmit_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.getchar = (getchar_t) spi_slave_hs_getch; + spi_slave_hs.device.get_char = (get_char_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 318698282c..22a7f56b66 100644 --- a/sw/airborne/arch/lpc21/usb_ser_hw.c +++ b/sw/airborne/arch/lpc21/usb_ser_hw.c @@ -621,5 +621,5 @@ void VCOM_init(void) usb_serial.device.transmit = (transmit_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.getchar = (getchar_t) usb_serial_getch; + usb_serial.device.get_char = (get_char_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 92e9368cba..1c010f688a 100644 --- a/sw/airborne/arch/stm32/usb_ser_hw.c +++ b/sw/airborne/arch/stm32/usb_ser_hw.c @@ -531,5 +531,5 @@ void VCOM_init(void) usb_serial.device.transmit = (transmit_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.getchar = (getchar_t) usb_serial_getch; + usb_serial.device.get_char = (get_char_t) usb_serial_getch; } diff --git a/sw/airborne/firmwares/fixedwing/fbw_datalink.c b/sw/airborne/firmwares/fixedwing/fbw_datalink.c index d1ab3c9734..f97f038e5e 100644 --- a/sw/airborne/firmwares/fixedwing/fbw_datalink.c +++ b/sw/airborne/firmwares/fixedwing/fbw_datalink.c @@ -68,8 +68,8 @@ void fbw_datalink_event(void) #endif while (ModemLinkDevice->char_available(ModemLinkDevice->periph)) - modem_parse(ModemLinkDevice->getchar(ModemLinkDevice->periph)); + modem_parse(ModemLinkDevice->get_char(ModemLinkDevice->periph)); while (AutopilotLinkDevice->char_available(AutopilotLinkDevice->periph)) - autopilot_parse(AutopilotLinkDevice->getchar(AutopilotLinkDevice->periph)); + autopilot_parse(AutopilotLinkDevice->get_char(AutopilotLinkDevice->periph)); } diff --git a/sw/airborne/mcu_periph/link_device.h b/sw/airborne/mcu_periph/link_device.h index cbfb1f413a..db33874943 100644 --- a/sw/airborne/mcu_periph/link_device.h +++ b/sw/airborne/mcu_periph/link_device.h @@ -37,7 +37,7 @@ typedef int (*check_free_space_t)(void *, uint8_t); typedef void (*transmit_t)(void *, uint8_t); typedef void (*send_message_t)(void *); typedef int (*char_available_t)(void *); -typedef uint8_t (*getchar_t)(void *); +typedef uint8_t (*get_char_t)(void *); /** Device structure */ @@ -46,7 +46,7 @@ struct link_device { transmit_t transmit; ///< transmit one byte send_message_t send_message; ///< send completed buffer char_available_t char_available; ///< check if a new character is available - getchar_t getchar; ///< get a new char + get_char_t get_char; ///< 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 74d78bd7d0..8408ea6e08 100644 --- a/sw/airborne/mcu_periph/uart.c +++ b/sw/airborne/mcu_periph/uart.c @@ -204,7 +204,7 @@ void uart_periph_init(struct uart_periph *p) p->device.transmit = (transmit_t)uart_transmit; p->device.send_message = (send_message_t)null_function; p->device.char_available = (char_available_t)uart_char_available; - p->device.getchar = (getchar_t)uart_getch; + p->device.get_char = (get_char_t)uart_getch; #if PERIODIC_TELEMETRY // the first to register do it for the others diff --git a/sw/airborne/mcu_periph/udp.c b/sw/airborne/mcu_periph/udp.c index 1472826a7b..c6e44a0c04 100644 --- a/sw/airborne/mcu_periph/udp.c +++ b/sw/airborne/mcu_periph/udp.c @@ -65,7 +65,7 @@ void udp_periph_init(struct udp_periph *p, char *host, int port_out, int port_in p->device.transmit = (transmit_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.getchar = (getchar_t) udp_getch; + p->device.get_char = (get_char_t) udp_getch; // Arch dependent initialization udp_arch_periph_init(p, host, port_out, port_in, broadcast); diff --git a/sw/airborne/modules/datalink/mavlink.h b/sw/airborne/modules/datalink/mavlink.h index cb9a66c791..f9b9d2f5b5 100644 --- a/sw/airborne/modules/datalink/mavlink.h +++ b/sw/airborne/modules/datalink/mavlink.h @@ -55,7 +55,7 @@ extern mavlink_system_t mavlink_system; #define MAVLinkDev (&(MAVLINK_DEV).device) #define MAVLinkTransmit(c) MAVLinkDev->transmit(MAVLinkDev->periph, c) #define MAVLinkChAvailable() MAVLinkDev->char_available(MAVLinkDev->periph) -#define MAVLinkGetch() MAVLinkDev->getchar(MAVLinkDev->periph) +#define MAVLinkGetch() MAVLinkDev->get_char(MAVLinkDev->periph) #define MAVLinkSendMessage() MAVLinkDev->send_message(MAVLinkDev->periph) /** diff --git a/sw/airborne/modules/datalink/mavlink_decoder.h b/sw/airborne/modules/datalink/mavlink_decoder.h index 424c709246..689bd23738 100644 --- a/sw/airborne/modules/datalink/mavlink_decoder.h +++ b/sw/airborne/modules/datalink/mavlink_decoder.h @@ -255,7 +255,7 @@ static inline void mavlink_check_and_parse(struct link_device *dev, struct mavli { if (dev->char_available(dev->periph)) { while (dev->char_available(dev->periph) && !trans->trans.msg_received) { - parse_mavlink(trans, dev->getchar(dev->periph)); + parse_mavlink(trans, dev->get_char(dev->periph)); } if (trans->trans.msg_received) { mavlink_parse_payload(trans); diff --git a/sw/airborne/modules/digital_cam/uart_cam_ctrl.c b/sw/airborne/modules/digital_cam/uart_cam_ctrl.c index 059d5cd0ee..f6d97fd7d0 100644 --- a/sw/airborne/modules/digital_cam/uart_cam_ctrl.c +++ b/sw/airborne/modules/digital_cam/uart_cam_ctrl.c @@ -48,7 +48,7 @@ #define CameraLinkDev (&(CAMERA_LINK).device) #define CameraLinkTransmit(c) CameraLinkDev->transmit(CameraLinkDev->periph, c) #define CameraLinkChAvailable() CameraLinkDev->check_available(CameraLinkDev->periph) -#define CameraLinkGetch() CameraLinkGetch->getchar(CameraLinkDev->periph) +#define CameraLinkGetch() CameraLinkGetch->get_char(CameraLinkDev->periph) union dc_shot_union dc_shot_msg; union mora_status_union mora_status_msg; diff --git a/sw/airborne/modules/ins/ahrs_chimu_spi.c b/sw/airborne/modules/ins/ahrs_chimu_spi.c index ab8005a00f..f9a5422c95 100644 --- a/sw/airborne/modules/ins/ahrs_chimu_spi.c +++ b/sw/airborne/modules/ins/ahrs_chimu_spi.c @@ -83,7 +83,7 @@ void parse_ins_msg(void) { struct link_device *dev = InsLinkDevice; while (dev->char_available(dev->periph)) { - uint8_t ch = dev->getchar(dev->periph); + uint8_t ch = dev->get_char(dev->periph); if (CHIMU_Parse(ch, 0, &CHIMU_DATA)) { RunOnceEvery(25, LED_TOGGLE(3)); diff --git a/sw/airborne/modules/ins/ahrs_chimu_uart.c b/sw/airborne/modules/ins/ahrs_chimu_uart.c index f1bf8261be..86719fde2e 100644 --- a/sw/airborne/modules/ins/ahrs_chimu_uart.c +++ b/sw/airborne/modules/ins/ahrs_chimu_uart.c @@ -74,7 +74,7 @@ void parse_ins_msg(void) { struct link_device *dev = InsLinkDevice; while (dev->char_available(dev->periph)) { - uint8_t ch = dev->getchar(dev->periph); + uint8_t ch = dev->get_char(dev->periph); if (CHIMU_Parse(ch, 0, &CHIMU_DATA)) { if (CHIMU_DATA.m_MsgID == 0x03) { diff --git a/sw/airborne/modules/ins/ins_module.h b/sw/airborne/modules/ins/ins_module.h index cbc952d762..a6b86b9756 100644 --- a/sw/airborne/modules/ins/ins_module.h +++ b/sw/airborne/modules/ins/ins_module.h @@ -91,7 +91,7 @@ static inline void ins_event_check_and_handle(void (* handler)(void)) struct link_device *dev = InsLinkDevice; if (dev->char_available(dev->periph)) { while (dev->char_available(dev->periph) && !ins_msg_received) { - parse_ins_buffer(dev->getchar(dev->periph)); + parse_ins_buffer(dev->get_char(dev->periph)); } } if (ins_msg_received) { diff --git a/sw/airborne/modules/sensors/met_module.h b/sw/airborne/modules/sensors/met_module.h index 68935abbab..1c5b647d9e 100644 --- a/sw/airborne/modules/sensors/met_module.h +++ b/sw/airborne/modules/sensors/met_module.h @@ -40,7 +40,7 @@ #define MetLinkDevice (&(MET_LINK).device) #define MetBuffer() MetLinkDevice->char_available(MetLinkDevice->periph) -#define MetGetch() MetLinkDevice->getchar(MetLinkDevice->periph) +#define MetGetch() MetLinkDevice->get_char(MetLinkDevice->periph) #define ReadMetBuffer() { while (MetBuffer()&&!met_msg_received) parse_met_buffer(MetGetch()); } #define MetSend1(c) MetLinkDevice->transmit(MetLinkDevice->periph, c) #define MetUartSend1(c) MetSend1(c) diff --git a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c index 030ac643af..556b7521aa 100644 --- a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c +++ b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c @@ -88,7 +88,7 @@ bool_t chibios_logInit(const bool_t binaryFile) chibios_sdlog.device.transmit = (transmit_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.getchar = (getchar_t) null_function; // write only + chibios_sdlog.device.get_char = (get_char_t) null_function; // write only if (sdLogInit (NULL) != SDLOG_OK) goto error; diff --git a/sw/airborne/subsystems/datalink/ivy_transport.c b/sw/airborne/subsystems/datalink/ivy_transport.c index 7b5cefb6ca..a978a7017f 100644 --- a/sw/airborne/subsystems/datalink/ivy_transport.c +++ b/sw/airborne/subsystems/datalink/ivy_transport.c @@ -199,6 +199,6 @@ void ivy_transport_init(void) ivy_tp.device.transmit = (transmit_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.getchar = (getchar_t) null_function; + ivy_tp.device.get_char = (get_char_t) null_function; ivy_tp.device.periph = (void *)(&ivy_tp); } diff --git a/sw/airborne/subsystems/datalink/pprz_transport.h b/sw/airborne/subsystems/datalink/pprz_transport.h index 0f53459f0a..7cb9d32757 100644 --- a/sw/airborne/subsystems/datalink/pprz_transport.h +++ b/sw/airborne/subsystems/datalink/pprz_transport.h @@ -146,7 +146,7 @@ static inline void pprz_check_and_parse(struct link_device *dev, struct pprz_tra { if (dev->char_available(dev->periph)) { while (dev->char_available(dev->periph) && !trans->trans_rx.msg_received) { - parse_pprz(trans, dev->getchar(dev->periph)); + parse_pprz(trans, dev->get_char(dev->periph)); } if (trans->trans_rx.msg_received) { pprz_parse_payload(trans); diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c index dd0d48b895..075e41c41a 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -246,7 +246,7 @@ void superbitrf_init(void) superbitrf.device.transmit = (transmit_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.getchar = (getchar_t) null_function; // not needed + superbitrf.device.get_char = (get_char_t) null_function; // not needed // Initialize the binding pin gpio_setup_input(SPEKTRUM_BIND_PIN_PORT, SPEKTRUM_BIND_PIN); diff --git a/sw/airborne/subsystems/datalink/w5100.c b/sw/airborne/subsystems/datalink/w5100.c index d705b5d9fc..d6530b7704 100644 --- a/sw/airborne/subsystems/datalink/w5100.c +++ b/sw/airborne/subsystems/datalink/w5100.c @@ -254,7 +254,7 @@ void w5100_init(void) chip0.device.transmit = (transmit_t) dev_transmit; chip0.device.send_message = (send_message_t) dev_send; chip0.device.char_available = (char_available_t) dev_char_available; - chip0.device.getchar = (getchar_t) dev_getch; + chip0.device.get_char = (get_char_t) dev_getch; } void w5100_transmit(uint8_t data) diff --git a/sw/airborne/subsystems/datalink/xbee.c b/sw/airborne/subsystems/datalink/xbee.c index 675938d3c1..2ba4db972b 100644 --- a/sw/airborne/subsystems/datalink/xbee.c +++ b/sw/airborne/subsystems/datalink/xbee.c @@ -126,7 +126,7 @@ static uint8_t xbee_text_reply_is_ok(struct link_device *dev) int count = 0; while (dev->char_available(dev->periph)) { - char cc = dev->getchar(dev->periph); + char cc = dev->get_char(dev->periph); if (count < 2) { c[count] = cc; } @@ -184,7 +184,7 @@ void xbee_init(void) // Empty buffer before init process while (dev->char_available(dev->periph)) { - dev->getchar(dev->periph); + dev->get_char(dev->periph); } #ifndef NO_XBEE_API_INIT diff --git a/sw/airborne/subsystems/datalink/xbee.h b/sw/airborne/subsystems/datalink/xbee.h index b4bc9f05eb..d4d0b175ff 100644 --- a/sw/airborne/subsystems/datalink/xbee.h +++ b/sw/airborne/subsystems/datalink/xbee.h @@ -140,7 +140,7 @@ static inline void xbee_check_and_parse(struct link_device *dev, struct xbee_tra { if (dev->char_available(dev->periph)) { while (dev->char_available(dev->periph) && !trans->trans_rx.msg_received) { - parse_xbee(trans, dev->getchar(dev->periph)); + parse_xbee(trans, dev->get_char(dev->periph)); } if (trans->trans_rx.msg_received) { xbee_parse_payload(trans); diff --git a/sw/airborne/subsystems/gps/gps_mtk.h b/sw/airborne/subsystems/gps/gps_mtk.h index ff799266a3..c89bc8526f 100644 --- a/sw/airborne/subsystems/gps/gps_mtk.h +++ b/sw/airborne/subsystems/gps/gps_mtk.h @@ -75,7 +75,7 @@ static inline void GpsEvent(void (* _sol_available_callback)(void)) if (dev->char_available(dev->periph)) { while (dev->char_available(dev->periph) && !gps_mtk.msg_available) { - gps_mtk_parse(dev->getchar(dev->periph)); + gps_mtk_parse(dev->get_char(dev->periph)); } GpsConfigure(); } diff --git a/sw/airborne/subsystems/gps/gps_nmea.h b/sw/airborne/subsystems/gps/gps_nmea.h index 08d2660a7d..d4c91adefb 100644 --- a/sw/airborne/subsystems/gps/gps_nmea.h +++ b/sw/airborne/subsystems/gps/gps_nmea.h @@ -69,7 +69,7 @@ static inline void GpsEvent(void (* _sol_available_callback)(void)) if (dev->char_available(dev->periph)) { while (dev->char_available(dev->periph)) { - nmea_parse_char(dev->getchar(dev->periph)); + nmea_parse_char(dev->get_char(dev->periph)); } } if (gps_nmea.msg_available) { diff --git a/sw/airborne/subsystems/gps/gps_sirf.h b/sw/airborne/subsystems/gps/gps_sirf.h index 4cd67b8e02..d30fa9d261 100644 --- a/sw/airborne/subsystems/gps/gps_sirf.h +++ b/sw/airborne/subsystems/gps/gps_sirf.h @@ -139,7 +139,7 @@ static inline void GpsEvent(void (* _sol_available_callback)(void)) if (dev->char_available(dev->periph)) { while (dev->char_available(dev->periph)) { - sirf_parse_char(dev->getchar(dev->periph)); + sirf_parse_char(dev->get_char(dev->periph)); } } if (gps_sirf.msg_available) { diff --git a/sw/airborne/subsystems/gps/gps_skytraq.h b/sw/airborne/subsystems/gps/gps_skytraq.h index 0ee2654004..c9331baad8 100644 --- a/sw/airborne/subsystems/gps/gps_skytraq.h +++ b/sw/airborne/subsystems/gps/gps_skytraq.h @@ -70,7 +70,7 @@ static inline void GpsEvent(void (* _sol_available_callback)(void)) if (dev->char_available(dev->periph)) { while (dev->char_available(dev->periph) && !gps_mtk.msg_available) { - gps_skytraq_parse(dev->getchar(dev->periph)); + gps_skytraq_parse(dev->get_char(dev->periph)); } } if (gps_skytraq.msg_available) { diff --git a/sw/airborne/subsystems/gps/gps_ubx.h b/sw/airborne/subsystems/gps/gps_ubx.h index f3637b6087..b55abd1622 100644 --- a/sw/airborne/subsystems/gps/gps_ubx.h +++ b/sw/airborne/subsystems/gps/gps_ubx.h @@ -104,7 +104,7 @@ static inline void GpsEvent(void (* _sol_available_callback)(void)) if (dev->char_available(dev->periph)) { while (dev->char_available(dev->periph) && !gps_ubx.msg_available) { - gps_ubx_parse(dev->getchar(dev->periph)); + gps_ubx_parse(dev->get_char(dev->periph)); } } if (gps_ubx.msg_available) {