rename getchar to get_char to avoid conflicts (like sdtio)

This commit is contained in:
Gautier Hattenberger
2015-03-18 18:10:15 +01:00
parent 083d21415d
commit eeb9075c91
26 changed files with 29 additions and 29 deletions
@@ -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;
}
+1 -1
View File
@@ -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;
}
+1 -1
View File
@@ -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;
}
@@ -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));
}
+2 -2
View File
@@ -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
};
+1 -1
View File
@@ -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
+1 -1
View File
@@ -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);
+1 -1
View File
@@ -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)
/**
@@ -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);
@@ -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;
+1 -1
View File
@@ -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));
+1 -1
View File
@@ -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) {
+1 -1
View File
@@ -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) {
+1 -1
View File
@@ -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)
@@ -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;
@@ -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);
}
@@ -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);
+1 -1
View File
@@ -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);
+1 -1
View File
@@ -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)
+2 -2
View File
@@ -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
+1 -1
View File
@@ -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);
+1 -1
View File
@@ -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();
}
+1 -1
View File
@@ -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) {
+1 -1
View File
@@ -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) {
+1 -1
View File
@@ -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) {
+1 -1
View File
@@ -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) {