libraries: rename purple to APM2

This commit is contained in:
Andrew Tridgell 2011-11-26 10:11:14 +11:00 committed by Pat Hickey
parent 3a542b3ef3
commit 02f25ac36d
15 changed files with 81 additions and 81 deletions

View File

@ -52,20 +52,20 @@ extern "C" {
//{
//}
// the purple hardware needs to check the state of the
// the apm2 hardware needs to check the state of the
// chip using a direct IO port
// On Purple prerelease hw, the data ready port is hooked up to PE7, which
// On APM2 prerelease hw, the data ready port is hooked up to PE7, which
// is not available to the arduino digitalRead function.
#define BMP_DATA_READY() (_purple_hardware?(PINE&0x80):digitalRead(BMP085_EOC))
#define BMP_DATA_READY() (_apm2_hardware?(PINE&0x80):digitalRead(BMP085_EOC))
// Public Methods //////////////////////////////////////////////////////////////
bool APM_BMP085_Class::Init(int initialiseWireLib, bool purple_hardware)
bool APM_BMP085_Class::Init(int initialiseWireLib, bool apm2_hardware)
{
byte buff[22];
int i = 0;
_purple_hardware = purple_hardware;
_apm2_hardware = apm2_hardware;
pinMode(BMP085_EOC, INPUT); // End Of Conversion (PC7) input

View File

@ -19,10 +19,10 @@ class APM_BMP085_Class
int32_t Press;
//int Altitude;
uint8_t oss;
bool _purple_hardware;
bool _apm2_hardware;
//int32_t Press0; // Pressure at sea level
bool Init(int initialiseWireLib = 1, bool purple_hardware=false);
bool Init(int initialiseWireLib = 1, bool apm2_hardware=false);
uint8_t Read();
private:

View File

@ -15,7 +15,7 @@ APM_BMP085_HIL_Class::APM_BMP085_HIL_Class()
}
// Public Methods //////////////////////////////////////////////////////////////
void APM_BMP085_HIL_Class::Init(int initialiseWireLib, bool purple_hardware)
void APM_BMP085_HIL_Class::Init(int initialiseWireLib, bool apm2_hardware)
{
BMP085_State=1;
}

View File

@ -13,7 +13,7 @@ class APM_BMP085_HIL_Class
int32_t Press;
//int Altitude;
uint8_t oss;
void Init(int initialiseWireLib = 1, bool purple_hardware=false);
void Init(int initialiseWireLib = 1, bool apm2_hardware=false);
uint8_t Read();
void setHIL(float Temp, float Press);
int32_t _offset_press;

View File

@ -13,10 +13,10 @@ unsigned long timer;
FastSerialPort0(Serial);
#ifdef PURPLE_HARDWARE
static bool purple_hardware = true;
#ifdef APM2_HARDWARE
static bool apm2_hardware = true;
#else
static bool purple_hardware = false;
static bool apm2_hardware = false;
#endif
void setup()
@ -24,7 +24,7 @@ void setup()
Serial.begin(115200);
Serial.println("ArduPilot Mega BMP085 library test");
Serial.println("Initialising barometer..."); delay(100);
if (!APM_BMP085.Init(1, purple_hardware)) {
if (!APM_BMP085.Init(1, apm2_hardware)) {
Serial.println("Barometer initialisation FAILED\n");
}
Serial.println("initialisation complete."); delay(100);

View File

@ -1,5 +1,5 @@
BOARD = mega
include ../../../AP_Common/Arduino.mk
purple:
make -f Makefile EXTRAFLAGS="-DPURPLE_HARDWARE=1"
apm2:
make -f Makefile EXTRAFLAGS="-DAPM2_HARDWARE=1"

View File

@ -46,6 +46,6 @@ class APM_RC_Class
};
#include "APM_RC_APM1.h"
#include "APM_RC_Purple.h"
#include "APM_RC_APM2.h"
#endif

View File

@ -1,5 +1,5 @@
/*
APM_RC_Purple.cpp - Radio Control Library for Ardupilot Mega 2.0. Arduino
APM_RC_APM2.cpp - Radio Control Library for Ardupilot Mega 2.0. Arduino
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
This library is free software; you can redistribute it and/or
@ -18,7 +18,7 @@
Automatically resets when we call InputCh to read channels
*/
#include "APM_RC_Purple.h"
#include "APM_RC_APM2.h"
#include "WProgram.h"
@ -27,13 +27,13 @@
#else
// Variable definition for Input Capture interrupt
volatile uint16_t APM_RC_Purple::_PWM_RAW[NUM_CHANNELS] = {2400,2400,2400,2400,2400,2400,2400,2400};
volatile uint8_t APM_RC_Purple::_radio_status=0;
volatile uint16_t APM_RC_APM2::_PWM_RAW[NUM_CHANNELS] = {2400,2400,2400,2400,2400,2400,2400,2400};
volatile uint8_t APM_RC_APM2::_radio_status=0;
/****************************************************
Input Capture Interrupt ICP5 => PPM signal read
****************************************************/
void APM_RC_Purple::_timer5_capt_cb(void)
void APM_RC_APM2::_timer5_capt_cb(void)
{
static uint16_t prev_icr;
static uint8_t frame_idx;
@ -68,12 +68,12 @@ void APM_RC_Purple::_timer5_capt_cb(void)
// Constructors ////////////////////////////////////////////////////////////////
APM_RC_Purple::APM_RC_Purple()
APM_RC_APM2::APM_RC_APM2()
{
}
// Public Methods //////////////////////////////////////////////////////////////
void APM_RC_Purple::Init( Arduino_Mega_ISR_Registry * isr_reg )
void APM_RC_APM2::Init( Arduino_Mega_ISR_Registry * isr_reg )
{
// --------------------- TIMER1: OUT1 and OUT2 -----------------------
pinMode(12,OUTPUT); // OUT1 (PB6/OC1B)
@ -147,7 +147,7 @@ void APM_RC_Purple::Init( Arduino_Mega_ISR_Registry * isr_reg )
TIMSK5 |= (1<<ICIE5);
}
void APM_RC_Purple::OutputCh(unsigned char ch, uint16_t pwm)
void APM_RC_APM2::OutputCh(unsigned char ch, uint16_t pwm)
{
pwm=constrain(pwm,MIN_PULSEWIDTH,MAX_PULSEWIDTH);
pwm<<=1; // pwm*2;
@ -165,7 +165,7 @@ void APM_RC_Purple::OutputCh(unsigned char ch, uint16_t pwm)
}
}
uint16_t APM_RC_Purple::InputCh(unsigned char ch)
uint16_t APM_RC_APM2::InputCh(unsigned char ch)
{
uint16_t result;
uint16_t result2;
@ -187,24 +187,24 @@ uint16_t APM_RC_Purple::InputCh(unsigned char ch)
return(result);
}
unsigned char APM_RC_Purple::GetState(void)
unsigned char APM_RC_APM2::GetState(void)
{
return(_radio_status);
}
// InstantPWM is not implemented!
void APM_RC_Purple::Force_Out(void) { }
void APM_RC_Purple::Force_Out0_Out1(void) { }
void APM_RC_Purple::Force_Out2_Out3(void) { }
void APM_RC_Purple::Force_Out6_Out7(void) { }
void APM_RC_APM2::Force_Out(void) { }
void APM_RC_APM2::Force_Out0_Out1(void) { }
void APM_RC_APM2::Force_Out2_Out3(void) { }
void APM_RC_APM2::Force_Out6_Out7(void) { }
/* ---------------- OUTPUT SPEED CONTROL ------------------ */
// Output rate options:
#define OUTPUT_SPEED_50HZ 0
#define OUTPUT_SPEED_200HZ 1
void APM_RC_Purple::SetFastOutputChannels(uint32_t chmask)
void APM_RC_APM2::SetFastOutputChannels(uint32_t chmask)
{
if ((chmask & ( MSK_CH_1 | MSK_CH_2 )) != 0)
_set_speed_ch1_ch2(OUTPUT_SPEED_200HZ);
@ -216,7 +216,7 @@ void APM_RC_Purple::SetFastOutputChannels(uint32_t chmask)
_set_speed_ch6_ch7_ch8(OUTPUT_SPEED_200HZ);
}
void APM_RC_Purple::_set_speed_ch1_ch2(uint8_t speed)
void APM_RC_APM2::_set_speed_ch1_ch2(uint8_t speed)
{
switch(speed) {
case OUTPUT_SPEED_200HZ:
@ -229,7 +229,7 @@ void APM_RC_Purple::_set_speed_ch1_ch2(uint8_t speed)
}
}
void APM_RC_Purple::_set_speed_ch3_ch4_ch5(uint8_t speed)
void APM_RC_APM2::_set_speed_ch3_ch4_ch5(uint8_t speed)
{
switch(speed) {
case OUTPUT_SPEED_200HZ:
@ -243,7 +243,7 @@ void APM_RC_Purple::_set_speed_ch3_ch4_ch5(uint8_t speed)
}
void APM_RC_Purple::_set_speed_ch6_ch7_ch8(uint8_t speed)
void APM_RC_APM2::_set_speed_ch6_ch7_ch8(uint8_t speed)
{
switch(speed) {
case OUTPUT_SPEED_200HZ:
@ -260,7 +260,7 @@ void APM_RC_Purple::_set_speed_ch6_ch7_ch8(uint8_t speed)
// allow HIL override of RC values
// A value of -1 means no change
// A value of 0 means no override, use the real RC values
bool APM_RC_Purple::setHIL(int16_t v[NUM_CHANNELS])
bool APM_RC_APM2::setHIL(int16_t v[NUM_CHANNELS])
{
uint8_t sum = 0;
for (unsigned char i=0; i<NUM_CHANNELS; i++) {
@ -279,7 +279,7 @@ bool APM_RC_Purple::setHIL(int16_t v[NUM_CHANNELS])
_radio_status = 1;
}
void APM_RC_Purple::clearOverride(void)
void APM_RC_APM2::clearOverride(void)
{
for (unsigned char i=0; i<NUM_CHANNELS; i++) {
_HIL_override[i] = 0;

View File

@ -1,5 +1,5 @@
#ifndef __APM_RC_PURPLE_H__
#define __APM_RC_PURPLE_H__
#ifndef __APM_RC_APM2_H__
#define __APM_RC_APM2_H__
#define NUM_CHANNELS 8
#define MIN_PULSEWIDTH 900
@ -8,11 +8,11 @@
#include "APM_RC.h"
#include "../Arduino_Mega_ISR_Registry/Arduino_Mega_ISR_Registry.h"
class APM_RC_Purple : public APM_RC_Class
class APM_RC_APM2 : public APM_RC_Class
{
private:
public:
APM_RC_Purple();
APM_RC_APM2();
void Init( Arduino_Mega_ISR_Registry * isr_reg );
void OutputCh(unsigned char ch, uint16_t pwm);
uint16_t InputCh(unsigned char ch);

View File

@ -10,7 +10,7 @@
#include <APM_RC.h> // ArduPilot Mega RC Library
Arduino_Mega_ISR_Registry isr_registry;
APM_RC_Purple APM_RC;
APM_RC_APM2 APM_RC;
void setup()
{

View File

@ -37,6 +37,6 @@ class DataFlash_Class
};
#include "DataFlash_APM1.h"
#include "DataFlash_Purple.h"
#include "DataFlash_APM2.h"
#endif

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
DataFlash_Purple.cpp - DataFlash log library for AT45DB321D
DataFlash_APM2.cpp - DataFlash log library for AT45DB321D
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
This code works only on ATMega2560. It uses Serial port 3 in SPI MSPI mdoe.
@ -39,7 +39,7 @@ extern "C" {
#include "WConstants.h"
}
#include "DataFlash_Purple.h"
#include "DataFlash_APM2.h"
// DataFlash is connected to Serial Port 3 (we will use SPI mode)
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
@ -79,7 +79,7 @@ extern "C" {
#define OVERWRITE_DATA 0 // 0: When reach the end page stop, 1: Start overwritten from page 1
// *** INTERNAL FUNCTIONS ***
unsigned char DataFlash_Purple::SPI_transfer(unsigned char data)
unsigned char DataFlash_APM2::SPI_transfer(unsigned char data)
{
/* Wait for empty transmit buffer */
while ( !( UCSR3A & (1<<UDRE3)) );
@ -91,23 +91,23 @@ unsigned char DataFlash_Purple::SPI_transfer(unsigned char data)
return UDR3;
}
void DataFlash_Purple::CS_inactive()
void DataFlash_APM2::CS_inactive()
{
digitalWrite(DF_SLAVESELECT,HIGH); //disable device
}
void DataFlash_Purple::CS_active()
void DataFlash_APM2::CS_active()
{
digitalWrite(DF_SLAVESELECT,LOW); //enable device
}
// Constructors ////////////////////////////////////////////////////////////////
DataFlash_Purple::DataFlash_Purple()
DataFlash_APM2::DataFlash_APM2()
{
}
// Public Methods //////////////////////////////////////////////////////////////
void DataFlash_Purple::Init(void)
void DataFlash_APM2::Init(void)
{
pinMode(DF_DATAOUT, OUTPUT);
pinMode(DF_DATAIN, INPUT);
@ -139,7 +139,7 @@ void DataFlash_Purple::Init(void)
}
// This function is mainly to test the device
void DataFlash_Purple::ReadManufacturerID()
void DataFlash_APM2::ReadManufacturerID()
{
CS_inactive(); // Reset dataflash command decoder
CS_active();
@ -154,13 +154,13 @@ void DataFlash_Purple::ReadManufacturerID()
}
// This function return 1 if Card is inserted on SD slot
bool DataFlash_Purple::CardInserted()
bool DataFlash_APM2::CardInserted()
{
return (digitalRead(DF_CARDDETECT) != 0);
}
// Read the status register
byte DataFlash_Purple::ReadStatusReg()
byte DataFlash_APM2::ReadStatusReg()
{
CS_inactive(); // Reset dataflash command decoder
CS_active();
@ -172,26 +172,26 @@ byte DataFlash_Purple::ReadStatusReg()
// Read the status of the DataFlash
inline
byte DataFlash_Purple::ReadStatus()
byte DataFlash_APM2::ReadStatus()
{
return(ReadStatusReg()&0x80); // We only want to extract the READY/BUSY bit
}
inline
uint16_t DataFlash_Purple::PageSize()
uint16_t DataFlash_APM2::PageSize()
{
return(528-((ReadStatusReg()&0x01)<<4)); // if first bit 1 trhen 512 else 528 bytes
}
// Wait until DataFlash is in ready state...
void DataFlash_Purple::WaitReady()
void DataFlash_APM2::WaitReady()
{
while(!ReadStatus());
}
void DataFlash_Purple::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
void DataFlash_APM2::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
{
CS_inactive();
CS_active();
@ -215,7 +215,7 @@ void DataFlash_Purple::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
}
void DataFlash_Purple::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
void DataFlash_APM2::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
{
CS_inactive(); // Reset dataflash command decoder
CS_active();
@ -242,7 +242,7 @@ void DataFlash_Purple::BufferToPage (unsigned char BufferNum, uint16_t PageAdr,
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
}
void DataFlash_Purple::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
void DataFlash_APM2::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
{
CS_inactive(); // Reset dataflash command decoder
CS_active();
@ -257,7 +257,7 @@ void DataFlash_Purple::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr
SPI_transfer(Data); //write data byte
}
unsigned char DataFlash_Purple::BufferRead (unsigned char BufferNum, uint16_t IntPageAdr)
unsigned char DataFlash_APM2::BufferRead (unsigned char BufferNum, uint16_t IntPageAdr)
{
byte tmp;
@ -278,7 +278,7 @@ unsigned char DataFlash_Purple::BufferRead (unsigned char BufferNum, uint16_t In
}
// *** END OF INTERNAL FUNCTIONS ***
void DataFlash_Purple::PageErase (uint16_t PageAdr)
void DataFlash_APM2::PageErase (uint16_t PageAdr)
{
CS_inactive(); //make sure to toggle CS signal in order
CS_active(); //to reset Dataflash command decoder
@ -299,7 +299,7 @@ void DataFlash_Purple::PageErase (uint16_t PageAdr)
}
void DataFlash_Purple::ChipErase ()
void DataFlash_APM2::ChipErase ()
{
CS_inactive(); //make sure to toggle CS signal in order
CS_active(); //to reset Dataflash command decoder
@ -315,7 +315,7 @@ void DataFlash_Purple::ChipErase ()
}
// *** DATAFLASH PUBLIC FUNCTIONS ***
void DataFlash_Purple::StartWrite(int16_t PageAdr)
void DataFlash_APM2::StartWrite(int16_t PageAdr)
{
df_BufferNum=1;
df_BufferIdx=4;
@ -330,7 +330,7 @@ void DataFlash_Purple::StartWrite(int16_t PageAdr)
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
}
void DataFlash_Purple::FinishWrite(void)
void DataFlash_APM2::FinishWrite(void)
{
df_BufferIdx=0;
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
@ -353,7 +353,7 @@ void DataFlash_Purple::FinishWrite(void)
}
void DataFlash_Purple::WriteByte(byte data)
void DataFlash_APM2::WriteByte(byte data)
{
if (!df_Stop_Write)
{
@ -389,13 +389,13 @@ void DataFlash_Purple::WriteByte(byte data)
}
}
void DataFlash_Purple::WriteInt(int16_t data)
void DataFlash_APM2::WriteInt(int16_t data)
{
WriteByte(data>>8); // High byte
WriteByte(data&0xFF); // Low byte
}
void DataFlash_Purple::WriteLong(int32_t data)
void DataFlash_APM2::WriteLong(int32_t data)
{
WriteByte(data>>24); // First byte
WriteByte(data>>16);
@ -404,18 +404,18 @@ void DataFlash_Purple::WriteLong(int32_t data)
}
// Get the last page written to
int16_t DataFlash_Purple::GetWritePage()
int16_t DataFlash_APM2::GetWritePage()
{
return(df_PageAdr);
}
// Get the last page read
int16_t DataFlash_Purple::GetPage()
int16_t DataFlash_APM2::GetPage()
{
return(df_Read_PageAdr-1);
}
void DataFlash_Purple::StartRead(int16_t PageAdr)
void DataFlash_APM2::StartRead(int16_t PageAdr)
{
df_Read_BufferNum=1;
df_Read_BufferIdx=4;
@ -431,7 +431,7 @@ void DataFlash_Purple::StartRead(int16_t PageAdr)
df_FilePage = (df_FilePage<<8) | BufferRead(df_Read_BufferNum,3); // Low byte
}
byte DataFlash_Purple::ReadByte()
byte DataFlash_APM2::ReadByte()
{
byte result;
@ -458,7 +458,7 @@ byte DataFlash_Purple::ReadByte()
return result;
}
int16_t DataFlash_Purple::ReadInt()
int16_t DataFlash_APM2::ReadInt()
{
uint16_t result;
@ -467,7 +467,7 @@ int16_t DataFlash_Purple::ReadInt()
return (int16_t)result;
}
int32_t DataFlash_Purple::ReadLong()
int32_t DataFlash_APM2::ReadLong()
{
uint32_t result;
@ -478,18 +478,18 @@ int32_t DataFlash_Purple::ReadLong()
return (int32_t)result;
}
void DataFlash_Purple::SetFileNumber(uint16_t FileNumber)
void DataFlash_APM2::SetFileNumber(uint16_t FileNumber)
{
df_FileNumber = FileNumber;
df_FilePage = 1;
}
uint16_t DataFlash_Purple::GetFileNumber()
uint16_t DataFlash_APM2::GetFileNumber()
{
return df_FileNumber;
}
uint16_t DataFlash_Purple::GetFilePage()
uint16_t DataFlash_APM2::GetFilePage()
{
return df_FilePage;
}

View File

@ -1,12 +1,12 @@
/* ************************************************************ */
/* DataFlash_Purple Log library */
/* DataFlash_APM2 Log library */
/* ************************************************************ */
#ifndef __DATAFLASH_PURPLE_H__
#define __DATAFLASH_PURPLE_H__
#ifndef __DATAFLASH_APM2_H__
#define __DATAFLASH_APM2_H__
#include "DataFlash.h"
class DataFlash_Purple : public DataFlash_Class
class DataFlash_APM2 : public DataFlash_Class
{
private:
// DataFlash Log variables...
@ -43,7 +43,7 @@ class DataFlash_Purple : public DataFlash_Class
unsigned char df_device_1;
uint16_t df_PageSize;
DataFlash_Purple(); // Constructor
DataFlash_APM2(); // Constructor
void Init();
void ReadManufacturerID();
bool CardInserted();

View File

@ -34,7 +34,7 @@ struct RC_ICR4 {
/*
ignore rate assignment for now (needed for purple
ignore rate assignment for now (needed for apm2
emulation)
*/
RC_ICR4& operator=(uint16_t rate) {