remove AP_Semaphore library, deprecated under AP_HAL

This commit is contained in:
Pat Hickey 2012-12-03 11:39:05 -08:00 committed by Andrew Tridgell
parent ec8b56db7d
commit db31608aa2
6 changed files with 0 additions and 224 deletions

View File

@ -1,70 +0,0 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#include "AP_Semaphore.h"
extern const AP_HAL::HAL& hal;
// Constructor
AP_Semaphore::AP_Semaphore()
{
}
// get - to claim ownership of the semaphore
bool AP_Semaphore::get(void* caller)
{
bool result = false;
hal.scheduler->begin_atomic();
if( !_taken ) {
_taken = true;
_owner = caller;
result = true;
}
hal.scheduler->end_atomic();
return result;
}
// release - to give up ownership of the semaphore
// returns true if successfully released
bool AP_Semaphore::release(void* caller)
{
// check legitimacy of release call
if( caller != _owner ) {
return false;
}
// if another process is waiting immediately call the provided kontinuation
if( _waiting_k != NULL ) {
// give ownership to waiting process
_owner = _waiting_owner;
AP_HAL::Proc k = _waiting_k;
// clear waiting process
_waiting_k = NULL;
_waiting_owner = NULL;
// callback
k();
}
// give up the semaphore
_taken = false;
return true;
}
// call_on_release - returns true if caller successfully added to the queue to
// be called back
bool AP_Semaphore::call_on_release(void* caller, AP_HAL::Proc k)
{
bool result = false;
hal.scheduler->begin_atomic();
if( _waiting_owner == NULL ) {
_waiting_owner = caller;
_waiting_k = k;
result = true;
}
hal.scheduler->end_atomic();
return result;
}

View File

@ -1,37 +0,0 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
/// @file AP_Semaphore.h
/// @brief class to ensure conflicts over shared resources are avoided
#ifndef __AP_SEMAPHORE_H__
#define __AP_SEMAPHORE_H__
#include <AP_HAL.h>
/// @class AP_Semaphore
class AP_Semaphore {
public:
// Constructor
AP_Semaphore();
// get - to claim ownership of the semaphore
virtual bool get(void* caller);
// release - to give up ownership of the semaphore
virtual bool release(void* caller);
// call_on_release - returns true if caller successfully added to the
// queue to be called back
virtual bool call_on_release(void* caller, AP_HAL::Proc k);
protected:
bool _taken;
void* _owner;
void* _waiting_owner;
// procedure of process waiting for sempahore
AP_HAL::Proc _waiting_k;
};
#endif // __AP_SEMAPHORE_H__

View File

@ -1,115 +0,0 @@
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_HAL.h>
#include <AP_Semaphore.h>
#include <AP_HAL_AVR.h>
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
static AP_Semaphore my_semaphore;
static AP_Semaphore AP_Semaphore_spi3;
int16_t dummy1, dummy2, dummy3; // used to provide points to semaphore library
// call back for dummy1
void callback_1() {
hal.console->println("dummy2 called back!");
}
// call back for dummy3
void callback_3() {
hal.console->println("dummy3 called back!");
}
void setup(void)
{
// print welcome message
hal.console->println("AP_Semaphore_test ver 1.0");
}
void print_test_result(bool expected, bool got) {
if( expected == got ) {
hal.console->print_P(PSTR("success: got "));
if (got) {
hal.console->println_P(PSTR("true"));
} else {
hal.console->println_P(PSTR("false"));
}
} else {
hal.console->printf_P(PSTR("***failed************************: expected %d got %d\r\n"),
(int)expected, (int) got);
}
}
void loop(void)
{
bool ret;
// quick test of spi semaphore
ret = AP_Semaphore_spi3.get(&dummy3);
hal.console->print("dummy3 gets SPI semaphore: ");
print_test_result(true, ret);
// dummy1 gets semaphore
hal.console->print("dummy1 gets semaphore: ");
ret = my_semaphore.get(&dummy1);
print_test_result(true, ret);
// dummy2 tries to get semaphore (fails)
hal.console->print("dummy2 gets semaphore: ");
ret = my_semaphore.get(&dummy2);
print_test_result(false, ret);
// dummy2 tries to release semaphore (fails)
hal.console->print("dummy2 releases semaphore (that it doesn't have): ");
ret = my_semaphore.release(&dummy2);
print_test_result(false, ret);
// dummy1 releases semaphore
hal.console->print("dummy1 releases semaphore: ");
ret = my_semaphore.release(&dummy1);
print_test_result(true, ret);
// dummy2 tries to get semaphore (succeeds)
hal.console->print("dummy2 gets semaphore: ");
ret = my_semaphore.get(&dummy2);
print_test_result(true, ret);
// dummy1 tries to get semphore (fails)
hal.console->print("dummy1 gets semaphore: ");
ret = my_semaphore.get(&dummy1);
print_test_result(false, ret);
// dummy1 asks for call back (succeeds)
hal.console->print("dummy1 asks for call back on release: ");
ret = my_semaphore.call_on_release(&dummy1, callback_1);
print_test_result(true, ret);
// dummy3 asks for call back (fails)
hal.console->print("dummy3 asks for call back on release: ");
ret = my_semaphore.call_on_release(&dummy3, callback_3);
print_test_result(false, ret);
// dummy2 releases semaphore
// dummy1's call back should be called
hal.console->print("dummy2 releases semaphore: ");
ret = my_semaphore.release(&dummy2);
print_test_result(true, ret);
hal.console->println("--------------------");
// nobody has semaphore
// delay
hal.scheduler->delay(10000);
}
extern "C" {
int main (void) {
hal.init(NULL);
setup();
for(;;) loop();
return 0;
}
}

View File

@ -1,2 +0,0 @@
BOARD = mega2560
include ../../../AP_Common/Arduino.mk