mirror of https://github.com/ArduPilot/ardupilot
Factor the Stream-related enhancements out from FastSerial proper, so that we could use them on other Stream subclasses if that seemed worthwhile.
Add print_P and println_P implementations to give folks wedded to the vanilla Stream methods a way to print PROGMEM strings. git-svn-id: https://arducopter.googlecode.com/svn/trunk@715 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
8eeb81f792
commit
271d4736a8
|
@ -0,0 +1,86 @@
|
|||
// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*-
|
||||
//
|
||||
// Copyright (c) 2010 Michael Smith. All rights reserved.
|
||||
//
|
||||
// This is free software; you can redistribute it and/or modify it under
|
||||
// the terms of the GNU Lesser General Public License as published by the
|
||||
// Free Software Foundation; either version 2.1 of the License, or (at
|
||||
// your option) any later version.
|
||||
//
|
||||
|
||||
//
|
||||
// Enhancements to the Arduino Stream class.
|
||||
//
|
||||
|
||||
#include "BetterStream.h"
|
||||
|
||||
// Stream extensions////////////////////////////////////////////////////////////
|
||||
|
||||
void
|
||||
BetterStream::print_P(const prog_char *s)
|
||||
{
|
||||
char c;
|
||||
|
||||
while ('\0' != (c = pgm_read_byte(s++)))
|
||||
write(c);
|
||||
}
|
||||
|
||||
void
|
||||
BetterStream::println_P(const char *s)
|
||||
{
|
||||
print_P(s);
|
||||
println();
|
||||
}
|
||||
|
||||
// STDIO emulation /////////////////////////////////////////////////////////////
|
||||
|
||||
int
|
||||
BetterStream::_putchar(char c, FILE *stream)
|
||||
{
|
||||
BetterStream *bs;
|
||||
|
||||
bs = (BetterStream *)fdev_get_udata(stream);
|
||||
if ('\n' == c)
|
||||
bs->write('\r'); // ASCII translation on the cheap
|
||||
bs->write(c);
|
||||
return(0);
|
||||
}
|
||||
|
||||
int
|
||||
BetterStream::_getchar(FILE *stream)
|
||||
{
|
||||
BetterStream *bs;
|
||||
|
||||
bs = (BetterStream *)fdev_get_udata(stream);
|
||||
|
||||
// We return -1 if there is nothing to read, which the library interprets
|
||||
// as an error, which our clients will need to deal with.
|
||||
return(bs->read());
|
||||
}
|
||||
|
||||
int
|
||||
BetterStream::printf(const char *fmt, ...)
|
||||
{
|
||||
va_list ap;
|
||||
int i;
|
||||
|
||||
va_start(ap, fmt);
|
||||
i = vfprintf(&fd, fmt, ap);
|
||||
va_end(ap);
|
||||
|
||||
return(i);
|
||||
}
|
||||
|
||||
int
|
||||
BetterStream::printf_P(const char *fmt, ...)
|
||||
{
|
||||
va_list ap;
|
||||
int i;
|
||||
|
||||
va_start(ap, fmt);
|
||||
i = vfprintf_P(&fd, fmt, ap);
|
||||
va_end(ap);
|
||||
|
||||
return(i);
|
||||
}
|
||||
|
|
@ -0,0 +1,38 @@
|
|||
// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*-
|
||||
//
|
||||
// Copyright (c) 2010 Michael Smith. All rights reserved.
|
||||
//
|
||||
// This is free software; you can redistribute it and/or modify it under
|
||||
// the terms of the GNU Lesser General Public License as published by the
|
||||
// Free Software Foundation; either version 2.1 of the License, or (at
|
||||
// your option) any later version.
|
||||
//
|
||||
|
||||
#include <Stream.h>
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
class BetterStream : public Stream {
|
||||
public:
|
||||
BetterStream(void) {
|
||||
// init stdio
|
||||
fdev_setup_stream(&fd, &BetterStream::_putchar, &BetterStream::_getchar, _FDEV_SETUP_RW);
|
||||
fdev_set_udata(&fd, this);
|
||||
}
|
||||
|
||||
// Stream extensions
|
||||
void print_P(const char *s);
|
||||
void println_P(const char *s);
|
||||
|
||||
// stdio extensions
|
||||
int printf(const char *fmt, ...);
|
||||
int printf_P(const char *fmt, ...);
|
||||
|
||||
protected:
|
||||
// subclasses can use this to e.g. set up stdin/stdout/stderr.
|
||||
FILE fd;
|
||||
|
||||
private:
|
||||
// stdio emulation
|
||||
static int _putchar(char c, FILE *stream);
|
||||
static int _getchar(FILE *stream);
|
||||
};
|
|
@ -102,13 +102,10 @@ FastSerial::FastSerial(const uint8_t portNumber,
|
|||
_txBuffer = &__FastSerial__txBuffer[portNumber];
|
||||
_rxBuffer->head = _rxBuffer->tail = 0;
|
||||
|
||||
// init stdio
|
||||
fdev_setup_stream(&_fd, &FastSerial::_putchar, &FastSerial::_getchar, _FDEV_SETUP_RW);
|
||||
fdev_set_udata(&_fd, this);
|
||||
if (0 == portNumber) {
|
||||
stdout = &_fd; // serial port 0 is always the default console
|
||||
stdin = &_fd;
|
||||
stderr = &_fd;
|
||||
stdout = &fd; // serial port 0 is always the default console
|
||||
stdin = &fd;
|
||||
stderr = &fd;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -259,58 +256,6 @@ FastSerial::write(uint8_t c)
|
|||
*_ucsrb |= _portTxBits;
|
||||
}
|
||||
|
||||
// STDIO emulation /////////////////////////////////////////////////////////////
|
||||
|
||||
int
|
||||
FastSerial::_putchar(char c, FILE *stream)
|
||||
{
|
||||
FastSerial *fs;
|
||||
|
||||
fs = (FastSerial *)fdev_get_udata(stream);
|
||||
if ('\n' == c)
|
||||
fs->write('\r'); // ASCII translation on the cheap
|
||||
fs->write(c);
|
||||
return(0);
|
||||
}
|
||||
|
||||
int
|
||||
FastSerial::_getchar(FILE *stream)
|
||||
{
|
||||
FastSerial *fs;
|
||||
|
||||
fs = (FastSerial *)fdev_get_udata(stream);
|
||||
|
||||
// We return -1 if there is nothing to read, which the library interprets
|
||||
// as an error, which our clients will need to deal with.
|
||||
return(fs->read());
|
||||
}
|
||||
|
||||
int
|
||||
FastSerial::printf(const char *fmt, ...)
|
||||
{
|
||||
va_list ap;
|
||||
int i;
|
||||
|
||||
va_start(ap, fmt);
|
||||
i = vfprintf(&_fd, fmt, ap);
|
||||
va_end(ap);
|
||||
|
||||
return(i);
|
||||
}
|
||||
|
||||
int
|
||||
FastSerial::printf_P(const char *fmt, ...)
|
||||
{
|
||||
va_list ap;
|
||||
int i;
|
||||
|
||||
va_start(ap, fmt);
|
||||
i = vfprintf_P(&_fd, fmt, ap);
|
||||
va_end(ap);
|
||||
|
||||
return(i);
|
||||
}
|
||||
|
||||
// Buffer management ///////////////////////////////////////////////////////////
|
||||
|
||||
bool
|
||||
|
|
|
@ -50,9 +50,10 @@
|
|||
#include <inttypes.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <Stream.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include "BetterStream.h"
|
||||
|
||||
//
|
||||
// Because Arduino libraries aren't really libraries, but we want to
|
||||
// only define interrupt handlers for serial ports that are actually
|
||||
|
@ -82,8 +83,7 @@ extern class FastSerial Serial1;
|
|||
extern class FastSerial Serial2;
|
||||
extern class FastSerial Serial3;
|
||||
|
||||
|
||||
class FastSerial : public Stream {
|
||||
class FastSerial : public BetterStream {
|
||||
public:
|
||||
FastSerial(const uint8_t portNumber,
|
||||
volatile uint8_t *ubrrh,
|
||||
|
@ -96,19 +96,14 @@ public:
|
|||
const uint8_t portTxBits);
|
||||
|
||||
// Serial API
|
||||
void begin(long baud);
|
||||
void begin(long baud, unsigned int rxSpace, unsigned int txSpace);
|
||||
void end(void);
|
||||
int available(void);
|
||||
int read(void);
|
||||
void flush(void);
|
||||
void write(uint8_t c);
|
||||
using Stream::write;
|
||||
|
||||
// stdio extensions
|
||||
int printf(const char *fmt, ...);
|
||||
int printf_P(const char *fmt, ...);
|
||||
FILE *getfd(void) { return &_fd; };
|
||||
virtual void begin(long baud);
|
||||
virtual void begin(long baud, unsigned int rxSpace, unsigned int txSpace);
|
||||
virtual void end(void);
|
||||
virtual int available(void);
|
||||
virtual int read(void);
|
||||
virtual void flush(void);
|
||||
virtual void write(uint8_t c);
|
||||
using BetterStream::write;
|
||||
|
||||
// public so the interrupt handlers can see it
|
||||
struct Buffer {
|
||||
|
@ -137,11 +132,6 @@ private:
|
|||
|
||||
bool _allocBuffer(Buffer *buffer, unsigned int size);
|
||||
void _freeBuffer(Buffer *buffer);
|
||||
|
||||
// stdio emulation
|
||||
FILE _fd;
|
||||
static int _putchar(char c, FILE *stream);
|
||||
static int _getchar(FILE *stream);
|
||||
};
|
||||
|
||||
// Used by the per-port interrupt vectors
|
||||
|
|
|
@ -38,6 +38,8 @@ void setup(void)
|
|||
// And send a message.
|
||||
//
|
||||
Serial.println("begin");
|
||||
Serial.printf("printf\n");
|
||||
Serial.println_P(PSTR("progmem"));
|
||||
}
|
||||
|
||||
void
|
||||
|
|
Loading…
Reference in New Issue