Skip to content

Commit

Permalink
Merge local and remote changes.
Browse files Browse the repository at this point in the history
  • Loading branch information
collin80 committed Nov 18, 2015
2 parents 40831c3 + 070851c commit cf64864
Show file tree
Hide file tree
Showing 5 changed files with 293 additions and 178 deletions.
126 changes: 121 additions & 5 deletions due_can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,9 @@ CANRaw::CANRaw(Can* pCan, uint32_t En ) {
m_pCan = pCan;
enablePin = En;
bigEndian = false;
busSpeed = 0;

for (int i = 0; i < 4; i++) listener[i] = NULL;
}

/**
Expand Down Expand Up @@ -117,6 +120,10 @@ uint32_t CANRaw::begin(uint32_t baudrate, uint8_t enablePin)
return init(baudrate);
}

uint32_t CANRaw::getBusSpeed()
{
return busSpeed;
}

/**
* \brief Initialize CAN controller.
Expand All @@ -132,6 +139,10 @@ uint32_t CANRaw::init(uint32_t ul_baudrate)
{
uint32_t ul_flag;
uint32_t ul_tick;

if (busSpeed == ul_baudrate) return ul_baudrate; //no need to reinitialize so just return that it was a success
else if (busSpeed != 0) return 0xFFFFFFFF; //ERROR! The bus was already initialized and you're trying to change it! Use set_baudrate if you really want to do that.


//initialize all function pointers to null
for (int i = 0; i < 9; i++) cbCANFrame[i] = 0;
Expand Down Expand Up @@ -176,14 +187,22 @@ uint32_t CANRaw::init(uint32_t ul_baudrate)
ul_tick++;
}

NVIC_SetPriority(m_pCan == CAN0 ? CAN0_IRQn : CAN1_IRQn, 12); //set a fairly low priority so almost anything can preempt
//set a fairly low priority so almost anything can preempt.
//this has the effect that most anything can interrupt our interrupt handler
//that's a good thing because the interrupt handler is long and complicated
//and can send callbacks into user code which could also be long and complicated.
//But, keep in mind that user code in callbacks runs in interrupt context
//but can still be preempted at any time.
NVIC_SetPriority(m_pCan == CAN0 ? CAN0_IRQn : CAN1_IRQn, 12);

NVIC_EnableIRQ(m_pCan == CAN0 ? CAN0_IRQn : CAN1_IRQn); //tell the nested interrupt controller to turn on our interrupt

/* Timeout or the CAN module has been synchronized with the bus. */
if (CAN_TIMEOUT == ul_tick) {
return 0;
} else {
return 1;
busSpeed = ul_baudrate;
return busSpeed;
}
}

Expand Down Expand Up @@ -255,6 +274,32 @@ void CANRaw::detachCANInterrupt(uint8_t mailBox)
cbCANFrame[mailBox] = 0;
}

boolean CANRaw::attachObj(CANListener *listener)
{
for (int i = 0; i < SIZE_LISTENERS; i++)
{
if (this->listener[i] == NULL)
{
this->listener[i] = listener;
listener->callbacksActive = 0;
return true;
}
}
return false;
}

boolean CANRaw::detachObj(CANListener *listener)
{
for (int i = 0; i < SIZE_LISTENERS; i++)
{
if (this->listener[i] == listener)
{
this->listener[i] = NULL;
return true;
}
}
return false;
}

/**
* \brief Enable CAN Controller.
Expand Down Expand Up @@ -1134,6 +1179,8 @@ int CANRaw::watchFor(uint32_t id, uint32_t mask)

//A bit more complicated. Makes sure that the range from id1 to id2 is let through. This might open
//the floodgates if you aren't careful.
//There are undoubtedly better ways to calculate the proper values for the filter but this way seems to work.
//It'll be kind of slow if you try to let a huge span through though.
int CANRaw::watchForRange(uint32_t id1, uint32_t id2)
{
int id = 0;
Expand Down Expand Up @@ -1207,9 +1254,12 @@ uint32_t CANRaw::getMailboxIer(int8_t mailbox) {
* \brief Handle a mailbox interrupt event
* \param mb which mailbox generated this event
* \param ul_status The status register of the canbus hardware
*
*/
void CANRaw::mailbox_int_handler(uint8_t mb, uint32_t ul_status) {
CAN_FRAME tempFrame;
boolean caughtFrame = false;
CANListener *thisListener;
if (mb > 7) mb = 7;
if (m_pCan->CAN_MB[mb].CAN_MSR & CAN_MSR_MRDY) { //mailbox signals it is ready
switch(((m_pCan->CAN_MB[mb].CAN_MMR >> 24) & 7)) { //what sort of mailbox is it?
Expand All @@ -1218,9 +1268,37 @@ void CANRaw::mailbox_int_handler(uint8_t mb, uint32_t ul_status) {
case 4: //consumer - technically still a receive buffer
mailbox_read(mb, &tempFrame);
//First, try to send a callback. If no callback registered then buffer the frame.
if (cbCANFrame[mb]) (*cbCANFrame[mb])(&tempFrame);
else if (cbCANFrame[8]) (*cbCANFrame[8])(&tempFrame);
else
if (cbCANFrame[mb])
{
caughtFrame = true;
(*cbCANFrame[mb])(&tempFrame);
}
else if (cbCANFrame[8])
{
caughtFrame = true;
(*cbCANFrame[8])(&tempFrame);
}
else
{
for (int listenerPos = 0; listenerPos < SIZE_LISTENERS; listenerPos++)
{
thisListener = listener[listenerPos];
if (thisListener != NULL)
{
if (thisListener->callbacksActive & (1 << mb))
{
caughtFrame = true;
thisListener->gotFrame(&tempFrame, mb);
}
else if (thisListener->callbacksActive & 256)
{
caughtFrame = true;
thisListener->gotFrame(&tempFrame, -1);
}
}
}
}
if (!caughtFrame) //if none of the callback types caught this frame then queue it in the buffer
{
uint8_t temp = (rx_buffer_head + 1) % SIZE_RX_BUFFER;
if (temp != rx_buffer_tail)
Expand Down Expand Up @@ -1251,6 +1329,44 @@ void CANRaw::mailbox_int_handler(uint8_t mb, uint32_t ul_status) {
}
}

CANListener::CANListener()
{
callbacksActive = 0; //none. Bitfield were bits 0-7 are the mailboxes and bit 8 is the general callback
}

//an empty version so that the linker doesn't complain that no implementation exists.
void CANListener::gotFrame(CAN_FRAME *frame, int mailbox)
{

}

void CANListener::attachMBHandler(uint8_t mailBox)
{
if (mailBox >= 0 && mailBox < 8)
{
callbacksActive |= (1<<mailBox);
}
}

void CANListener::detachMBHandler(uint8_t mailBox)
{
if (mailBox >= 0 && mailBox < 8)
{
callbacksActive &= ~(1<<mailBox);
}
}

void CANListener::attachGeneralHandler()
{
callbacksActive |= 256;
}

void CANListener::detachGeneralHandler()
{
callbacksActive &= ~256;
}


/**
* \brief Interrupt dispatchers - Never directly call these
*
Expand Down
120 changes: 76 additions & 44 deletions due_can.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@
#define CAN Can0
#define CAN2 Can1

#define CAN0_EN 62
#define CAN1_EN 65
#define CAN0_EN 50 //these enable pins match most all recent EVTV boards (EVTVDue, CAN Due 2.0)
#define CAN1_EN 48 //they're only defaults, you can set whichever pin you need when calling begin()

/** Define the Mailbox mask for eight mailboxes. */
#define GLOBAL_MAILBOX_MASK 0x000000ff
Expand All @@ -46,28 +46,29 @@
#define CAN_DISABLE_ALL_INTERRUPT_MASK 0xffffffff

/** Define the typical baudrate for CAN communication. */
#ifdef CAN_BPS_1000K
#undef CAN_BPS_1000K
#undef CAN_BPS_800K
#undef CAN_BPS_500K
#undef CAN_BPS_250K
#undef CAN_BPS_125K
#undef CAN_BPS_50K
#undef CAN_BPS_33333
#undef CAN_BPS_25K
#undef CAN_BPS_10K
#undef CAN_BPS_5K
#ifdef CAN_BPS_500K
#undef CAN_BPS_1000K
#undef CAN_BPS_800K
#undef CAN_BPS_500K
#undef CAN_BPS_250K
#undef CAN_BPS_125K
#undef CAN_BPS_50K
#undef CAN_BPS_33333
#undef CAN_BPS_25K
#undef CAN_BPS_10K
#undef CAN_BPS_5K
#endif
#define CAN_BPS_1000K 1000000
#define CAN_BPS_800K 800000
#define CAN_BPS_500K 500000
#define CAN_BPS_250K 250000
#define CAN_BPS_125K 125000
#define CAN_BPS_50K 50000
#define CAN_BPS_33333 33333
#define CAN_BPS_25K 25000
#define CAN_BPS_10K 10000
#define CAN_BPS_5K 5000

#define CAN_BPS_1000K 1000000
#define CAN_BPS_800K 800000
#define CAN_BPS_500K 500000
#define CAN_BPS_250K 250000
#define CAN_BPS_125K 125000
#define CAN_BPS_50K 50000
#define CAN_BPS_33333 33333
#define CAN_BPS_25K 25000
#define CAN_BPS_10K 10000
#define CAN_BPS_5K 5000

#define CAN_DEFAULT_BAUD CAN_BPS_250K

Expand All @@ -87,6 +88,7 @@

#define SIZE_RX_BUFFER 32 //RX incoming ring buffer is this big
#define SIZE_TX_BUFFER 16 //TX ring buffer is this big
#define SIZE_LISTENERS 4 //number of classes that can register as listeners with this class

/** Define the timemark mask. */
#define TIMEMARK_MASK 0x0000ffff
Expand Down Expand Up @@ -146,7 +148,7 @@ typedef union {
uint32_t high;
};
struct {
uint16_t s0;
uint16_t s0;
uint16_t s1;
uint16_t s2;
uint16_t s3;
Expand All @@ -166,6 +168,24 @@ typedef struct
BytesUnion data; // 64 bits - lots of ways to access it.
} CAN_FRAME;

class CANListener
{
public:
CANListener();

virtual void gotFrame(CAN_FRAME *frame, int mailbox);

void attachMBHandler(uint8_t mailBox);
void detachMBHandler(uint8_t mailBox);
void attachGeneralHandler();
void detachGeneralHandler();

private:
int callbacksActive; //bitfield letting the code know which callbacks to actually try to use (for object oriented callbacks only)

friend class CANRaw; //class has to have access to the the guts of this one
};

class CANRaw
{
protected:
Expand All @@ -183,10 +203,13 @@ class CANRaw
void mailbox_int_handler(uint8_t mb, uint32_t ul_status);

uint8_t enablePin;
uint32_t busSpeed; //what speed is the bus currently initialized at? 0 if it is off right now

uint32_t write_id; //public storage for an id. Will be used by the write function to set which ID to send to.
bool bigEndian;

void (*cbCANFrame[9])(CAN_FRAME *); //8 mailboxes plus an optional catch all
CANListener *listener[SIZE_LISTENERS];

public:

Expand All @@ -211,9 +234,38 @@ class CANRaw
uint32_t begin();
uint32_t begin(uint32_t baudrate);
uint32_t begin(uint32_t baudrate, uint8_t enablePin);
uint32_t getBusSpeed();

void enable();
void disable();

bool sendFrame(CAN_FRAME& txFrame);
void setWriteID(uint32_t id);
template <typename t> void write(t inputValue); //write a variable # of bytes out in a frame. Uses id as the ID.
void setBigEndian(bool);

void setCallback(int mailbox, void (*cb)(CAN_FRAME *));
void setGeneralCallback(void (*cb)(CAN_FRAME *));
//note that these below versions still use mailbox number. There isn't a good way around this.
void attachCANInterrupt(void (*cb)(CAN_FRAME *)); //alternative callname for setGeneralCallback
void attachCANInterrupt(uint8_t mailBox, void (*cb)(CAN_FRAME *));
void detachCANInterrupt(uint8_t mailBox);

//now, object oriented versions to make OO projects easier
boolean attachObj(CANListener *listener);
boolean detachObj(CANListener *listener);

void reset_all_mailbox();
void interruptHandler();
bool rx_avail();
int available(); //like rx_avail but returns the number of waiting frames

uint32_t get_rx_buff(CAN_FRAME &);
uint32_t read(CAN_FRAME &);

//misc old cruft kept around just in case anyone actually used any of it in older code.
//some are used within the functions above. Unless you really know of a good reason to use
//any of these you probably should steer clear of them.
void disable_low_power_mode();
void enable_low_power_mode();
void disable_autobaud_listen_mode();
Expand Down Expand Up @@ -254,26 +306,6 @@ class CANRaw
void mailbox_set_datalen(uint8_t uc_index, uint8_t dlen);
void mailbox_set_datal(uint8_t uc_index, uint32_t val);
void mailbox_set_datah(uint8_t uc_index, uint32_t val);

bool sendFrame(CAN_FRAME& txFrame);
void setWriteID(uint32_t id);
template <typename t> void write(t inputValue); //write a variable # of bytes out in a frame. Uses id as the ID.
void setBigEndian(bool);

void setCallback(int mailbox, void (*cb)(CAN_FRAME *));
void setGeneralCallback(void (*cb)(CAN_FRAME *));
//note that these below versions still use mailbox number. There isn't a good way around this.
void attachCANInterrupt(void (*cb)(CAN_FRAME *)); //alternative callname for setGeneralCallback
void attachCANInterrupt(uint8_t mailBox, void (*cb)(CAN_FRAME *));
void detachCANInterrupt(uint8_t mailBox);

void reset_all_mailbox();
void interruptHandler();
bool rx_avail();
int available(); //like rx_avail but returns the number of waiting frames

uint32_t get_rx_buff(CAN_FRAME &);
uint32_t read(CAN_FRAME &);
};

extern CANRaw Can0;
Expand Down
Loading

0 comments on commit cf64864

Please sign in to comment.