AP_HAL_AVR_SITL: implement BetterStream's vprintf methods

This commit is contained in:
Pat Hickey 2012-12-19 14:01:50 -08:00 committed by Andrew Tridgell
parent 1ed6a49a7a
commit 823efc4734
6 changed files with 31 additions and 9 deletions

View File

@ -6,7 +6,7 @@
#include <limits.h>
#include <stdarg.h>
#include "Console.h"
#include "vprintf.h"
#include "print_vprintf.h"
using namespace AVR_SITL;
@ -57,18 +57,28 @@ void SITLConsoleDriver::printf(const char *fmt, ...)
{
va_list ap;
va_start(ap, fmt);
vprintf((AP_HAL::Print*)this, 0, fmt, ap);
vprintf(fmt, ap);
va_end(ap);
}
void SITLConsoleDriver::vprintf(const char *fmt, va_list ap)
{
print_vprintf((AP_HAL::Print*)this, 0, fmt, ap);
}
void SITLConsoleDriver::_printf_P(const prog_char *fmt, ...)
{
va_list ap;
va_start(ap, fmt);
vprintf((AP_HAL::Print*)this, 1, fmt, ap);
vprintf_P(fmt, ap);
va_end(ap);
}
void SITLConsoleDriver::vprintf_P(const prog_char *fmt, va_list ap)
{
print_vprintf((AP_HAL::Print*)this, 1, fmt, ap);
}
// Stream method implementations /////////////////////////////////////////
int16_t SITLConsoleDriver::available(void)
{

View File

@ -25,6 +25,9 @@ public:
void _printf_P(const prog_char *s, ...)
__attribute__ ((format(__printf__, 2, 3)));
void vprintf(const char *s, va_list ap);
void vprintf_P(const prog_char *s, va_list ap);
/* Implementations of Stream virtual methods */
int16_t available();
int16_t txspace();

View File

@ -25,7 +25,7 @@
#include <netinet/in.h>
#include <netinet/tcp.h>
#include "vprintf.h"
#include "print_vprintf.h"
#include "UARTDriver.h"
#include "SITL_State.h"
@ -182,18 +182,25 @@ void SITLUARTDriver::printf(const char *fmt, ...)
{
va_list ap;
va_start(ap, fmt);
vprintf((AP_HAL::Print*)this, 0, fmt, ap);
vprintf(fmt, ap);
va_end(ap);
}
void SITLUARTDriver::vprintf(const char *fmt, va_list ap) {
print_vprintf((AP_HAL::Print*)this, 0, fmt, ap);
}
void SITLUARTDriver::_printf_P(const prog_char *fmt, ...)
{
va_list ap;
va_start(ap, fmt);
vprintf((AP_HAL::Print*)this, 1, fmt, ap);
vprintf_P(fmt, ap);
va_end(ap);
}
void SITLUARTDriver::vprintf_P(const prog_char *fmt, va_list ap) {
print_vprintf((AP_HAL::Print*)this, 1, fmt, ap);
}
/*
start a TCP connection for the serial port. If wait_for_connection
is true then block until a client connects

View File

@ -46,6 +46,8 @@ public:
__attribute__ ((format(__printf__, 2, 3)));
void _printf_P(const prog_char *s, ...)
__attribute__ ((format(__printf__, 2, 3)));
void vprintf(const char *s, va_list ap);
void vprintf_P(const prog_char *s, va_list ap);
/* Implementations of Stream virtual methods */
int16_t available();

View File

@ -14,11 +14,11 @@
#include <AP_Progmem.h>
#include <stdarg.h>
#include <string.h>
#include "vprintf.h"
#include "print_vprintf.h"
#include <stdio.h>
#include <stdlib.h>
void vprintf(AP_HAL::Print *s, unsigned char in_progmem, const char *fmt, va_list ap)
void print_vprintf(AP_HAL::Print *s, unsigned char in_progmem, const char *fmt, va_list ap)
{
char *str = NULL;
int i;

View File

@ -5,7 +5,7 @@
#include <AP_HAL.h>
#include <stdarg.h>
void vprintf (AP_HAL::Print *s, unsigned char in_progmem, const char *fmt, va_list ap);
void print_vprintf (AP_HAL::Print *s, unsigned char in_progmem, const char *fmt, va_list ap);
#endif //__AP_HAL_AVR_SITL_UTILITY_VPRINTF_H__