Modified to run on Renesas GR Peach board
Dependencies: EthernetInterface HTTP-Server Webpage mbed-rpc mbed-src
Fork of HTTPServer_echoback by
Revision 16:5d102be2566c, committed 2015-10-07
- Comitter:
- webOnBoard
- Date:
- Wed Oct 07 20:42:51 2015 +0000
- Parent:
- 15:eae1575da9ca
- Commit message:
- web based AHRS demo Renesas GR Peach board; Using HTTP Server/RPC Adafruit 10DOF
Changed in this revision
diff -r eae1575da9ca -r 5d102be2566c Adafruit_10DOF/Adafruit_10DOF.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Adafruit_10DOF/Adafruit_10DOF.cpp Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,353 @@ +/*************************************************************************** + This is a library for the Adafruit 10DOF Breakout + + Designed specifically to work with the Adafruit 10DOF Breakout + + These displays use I2C to communicate, 2 pins are required to interface. + + Adafruit invests time and resources providing this open source code, + please support Adafruit andopen-source hardware by purchasing products + from Adafruit! + + Written by Kevin Townsend for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ***************************************************************************/ + + //#include "WProgram.h" + + +#include "Adafruit_10DOF.h" +#include "Adafruit_Sensor.h" +#include "I2C.h" + +#define PI (3.14159265F); + +/*************************************************************************** + PRIVATE FUNCTIONS + ***************************************************************************/ + + +/*************************************************************************** + CONSTRUCTOR + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Instantiates a new Adafruit_10DOF class +*/ +/**************************************************************************/ +Adafruit_10DOF::Adafruit_10DOF(void) +{ +} + +/*************************************************************************** + PUBLIC FUNCTIONS + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Setups the HW +*/ +/**************************************************************************/ +bool Adafruit_10DOF::begin() +{ + // Enable I2C + //Wire.begin(); + + return true; +} + +/**************************************************************************/ +/*! + @brief Populates the .pitch/.roll fields in the sensors_vec_t struct + with the right angular data (in degree) + + @param event The sensors_event_t variable containing the + data from the accelerometer + @param orientation The sensors_vec_t object that will have it's + .pitch and .roll fields populated + @return Returns true if the operation was successful, false if there + was an error + + @code + + bool error; + sensors_event_t event; + sensors_vec_t orientation; + ... + lsm303accelGetSensorEvent(&event); + error = accelGetOrientation(&event, &orientation); + + @endcode +*/ +/**************************************************************************/ +bool Adafruit_10DOF::accelGetOrientation(sensors_event_t *event, sensors_vec_t *orientation) +{ + /* Make sure the input is valid, not null, etc. */ + if (event == NULL) return false; + if (orientation == NULL) return false; + + float t_pitch; + float t_roll; + float t_heading; + float signOfZ = event->acceleration.z >= 0 ? 1.0F : -1.0F; + + /* roll: Rotation around the longitudinal axis (the plane body, 'X axis'). -90<=roll<=90 */ + /* roll is positive and increasing when moving downward */ + /* */ + /* y */ + /* roll = atan(-----------------) */ + /* sqrt(x^2 + z^2) */ + /* where: x, y, z are returned value from accelerometer sensor */ + + t_roll = event->acceleration.x * event->acceleration.x + event->acceleration.z * event->acceleration.z; + orientation->roll = (float)atan2(event->acceleration.y, sqrt(t_roll)) * 180 / PI; + + /* pitch: Rotation around the lateral axis (the wing span, 'Y axis'). -180<=pitch<=180) */ + /* pitch is positive and increasing when moving upwards */ + /* */ + /* x */ + /* pitch = atan(-----------------) */ + /* sqrt(y^2 + z^2) */ + /* where: x, y, z are returned value from accelerometer sensor */ + + t_pitch = event->acceleration.y * event->acceleration.y + event->acceleration.z * event->acceleration.z; + orientation->pitch = (float)atan2(event->acceleration.x, signOfZ * sqrt(t_pitch)) * 180 / PI; + + return true; +} + +/**************************************************************************/ +/*! + @brief Utilize the sensor data from an accelerometer to compensate + the magnetic sensor measurements when the sensor is tilted + (the pitch and roll angles are not equal 0°) + + @param axis The given axis (SENSOR_AXIS_X/Y/Z) that is + parallel to the gravity of the Earth + + @param mag_event The raw magnetometer data to adjust for tilt + + @param accel_event The accelerometer event data to use to determine + the tilt when compensating the mag_event values + + @code + + // Perform tilt compensation with matching accelerometer data + sensors_event_t accel_event; + error = lsm303accelGetSensorEvent(&accel_event); + if (!error) + { + magTiltCompensation(SENSOR_AXIS_Z, &mag_event, &accel_event); + } + + @endcode +*/ +/**************************************************************************/ +bool Adafruit_10DOF::magTiltCompensation(sensors_axis_t axis, sensors_event_t *mag_event, sensors_event_t *accel_event) +{ + /* Make sure the input is valid, not null, etc. */ + if (mag_event == NULL) return false; + if (accel_event == NULL) return false; + + float accel_X, accel_Y, accel_Z; + float *mag_X, *mag_Y, *mag_Z; + + switch (axis) + { + case SENSOR_AXIS_X: + /* The X-axis is parallel to the gravity */ + accel_X = accel_event->acceleration.y; + accel_Y = accel_event->acceleration.z; + accel_Z = accel_event->acceleration.x; + mag_X = &(mag_event->magnetic.y); + mag_Y = &(mag_event->magnetic.z); + mag_Z = &(mag_event->magnetic.x); + break; + + case SENSOR_AXIS_Y: + /* The Y-axis is parallel to the gravity */ + accel_X = accel_event->acceleration.z; + accel_Y = accel_event->acceleration.x; + accel_Z = accel_event->acceleration.y; + mag_X = &(mag_event->magnetic.z); + mag_Y = &(mag_event->magnetic.x); + mag_Z = &(mag_event->magnetic.y); + break; + + case SENSOR_AXIS_Z: + /* The Z-axis is parallel to the gravity */ + accel_X = accel_event->acceleration.x; + accel_Y = accel_event->acceleration.y; + accel_Z = accel_event->acceleration.z; + mag_X = &(mag_event->magnetic.x); + mag_Y = &(mag_event->magnetic.y); + mag_Z = &(mag_event->magnetic.z); + break; + + default: + return false; + } + + float t_roll = accel_X * accel_X + accel_Z * accel_Z; + float rollRadians = (float)atan2(accel_Y, sqrt(t_roll)); + + float t_pitch = accel_Y * accel_Y + accel_Z * accel_Z; + float pitchRadians = (float)atan2(accel_X, sqrt(t_pitch)); + + float cosRoll = (float)cos(rollRadians); + float sinRoll = (float)sin(rollRadians); + float cosPitch = (float)cos(-1*pitchRadians); + float sinPitch = (float)sin(-1*pitchRadians); + + /* The tilt compensation algorithm */ + /* Xh = X.cosPitch + Z.sinPitch */ + /* Yh = X.sinRoll.sinPitch + Y.cosRoll - Z.sinRoll.cosPitch */ + *mag_X = (*mag_X) * cosPitch + (*mag_Z) * sinPitch; + *mag_Y = (*mag_X) * sinRoll * sinPitch + (*mag_Y) * cosRoll - (*mag_Z) * sinRoll * cosPitch; + + return true; +} + +/**************************************************************************/ +/*! + @brief Populates the .heading fields in the sensors_vec_t + struct with the right angular data (0-359°) + + Heading increases when measuring clockwise + + @param axis The given axis (SENSOR_AXIS_X/Y/Z) + + @param event The raw magnetometer sensor data to use when + calculating out heading + + @param orientation The sensors_vec_t object where we will + assign an 'orientation.heading' value + + @code + + magGetOrientation(SENSOR_AXIS_Z, &mag_event, &orientation); + + @endcode +*/ +/**************************************************************************/ +bool Adafruit_10DOF::magGetOrientation(sensors_axis_t axis, sensors_event_t *event, sensors_vec_t *orientation) +{ + /* Make sure the input is valid, not null, etc. */ + if (event == NULL) return false; + if (orientation == NULL) return false; + + switch (axis) + { + case SENSOR_AXIS_X: + /* Sensor rotates around X-axis */ + /* "heading" is the angle between the 'Y axis' and magnetic north on the horizontal plane (Oyz) */ + /* heading = atan(Mz / My) */ + orientation->heading = (float)atan2(event->magnetic.z, event->magnetic.y) * 180 / PI; + break; + + case SENSOR_AXIS_Y: + /* Sensor rotates around Y-axis */ + /* "heading" is the angle between the 'Z axis' and magnetic north on the horizontal plane (Ozx) */ + /* heading = atan(Mx / Mz) */ + orientation->heading = (float)atan2(event->magnetic.x, event->magnetic.z) * 180 / PI; + break; + + case SENSOR_AXIS_Z: + /* Sensor rotates around Z-axis */ + /* "heading" is the angle between the 'X axis' and magnetic north on the horizontal plane (Oxy) */ + /* heading = atan(My / Mx) */ + orientation->heading = (float)atan2(event->magnetic.y, event->magnetic.x) * 180 / PI; + break; + + default: + return false; + } + + /* Normalize to 0-359° */ + if (orientation->heading < 0) + { + orientation->heading = 360 + orientation->heading; + } + + return true; +} + +/**************************************************************************/ +/*! + @brief Populates the .roll/.pitch/.heading fields in the sensors_vec_t + struct with the right angular data (in degree). + + The starting position is set by placing the object flat and + pointing northwards (Z-axis pointing upward and X-axis pointing + northwards). + + The orientation of the object can be modeled as resulting from + 3 consecutive rotations in turn: heading (Z-axis), pitch (Y-axis), + and roll (X-axis) applied to the starting position. + + + @param accel_event The sensors_event_t variable containing the + data from the accelerometer + + @param mag_event The sensors_event_t variable containing the + data from the magnetometer + + @param orientation The sensors_vec_t object that will have it's + .roll, .pitch and .heading fields populated +*/ +/**************************************************************************/ +bool Adafruit_10DOF::fusionGetOrientation(sensors_event_t *accel_event, sensors_event_t *mag_event, sensors_vec_t *orientation) +{ + /* Make sure the input is valid, not null, etc. */ + if ( accel_event == NULL) return false; + if ( mag_event == NULL) return false; + if ( orientation == NULL) return false; + + float const PI_F = 3.14159265F; + + /* roll: Rotation around the X-axis. -180 <= roll <= 180 */ + /* a positive roll angle is defined to be a clockwise rotation about the positive X-axis */ + /* */ + /* y */ + /* roll = atan2(---) */ + /* z */ + /* */ + /* where: y, z are returned value from accelerometer sensor */ + orientation->roll = (float)atan2(accel_event->acceleration.y, accel_event->acceleration.z); + + /* pitch: Rotation around the Y-axis. -180 <= roll <= 180 */ + /* a positive pitch angle is defined to be a clockwise rotation about the positive Y-axis */ + /* */ + /* -x */ + /* pitch = atan(-------------------------------) */ + /* y * sin(roll) + z * cos(roll) */ + /* */ + /* where: x, y, z are returned value from accelerometer sensor */ + if (accel_event->acceleration.y * sin(orientation->roll) + accel_event->acceleration.z * cos(orientation->roll) == 0) + orientation->pitch = accel_event->acceleration.x > 0 ? (PI_F / 2) : (-PI_F / 2); + else + orientation->pitch = (float)atan(-accel_event->acceleration.x / (accel_event->acceleration.y * sin(orientation->roll) + \ + accel_event->acceleration.z * cos(orientation->roll))); + + /* heading: Rotation around the Z-axis. -180 <= roll <= 180 */ + /* a positive heading angle is defined to be a clockwise rotation about the positive Z-axis */ + /* */ + /* z * sin(roll) - y * cos(roll) */ + /* heading = atan2(--------------------------------------------------------------------------) */ + /* x * cos(pitch) + y * sin(pitch) * sin(roll) + z * sin(pitch) * cos(roll)) */ + /* */ + /* where: x, y, z are returned value from magnetometer sensor */ + orientation->heading = (float)atan2(mag_event->magnetic.z * sin(orientation->roll) - mag_event->magnetic.y * cos(orientation->roll), \ + mag_event->magnetic.x * cos(orientation->pitch) + \ + mag_event->magnetic.y * sin(orientation->pitch) * sin(orientation->roll) + \ + mag_event->magnetic.z * sin(orientation->pitch) * cos(orientation->roll)); + + + /* Convert angular data to degree */ + orientation->roll = orientation->roll * 180 / PI_F; + orientation->pitch = orientation->pitch * 180 / PI_F; + orientation->heading = orientation->heading * 180 / PI_F; + + return true; +}
diff -r eae1575da9ca -r 5d102be2566c Adafruit_10DOF/Adafruit_10DOF.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Adafruit_10DOF/Adafruit_10DOF.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,48 @@ +/*************************************************************************** + This is a library for the Adafruit 10DOF Breakout + + Designed specifically to work with the Adafruit 10DOF Breakout + + These displays use I2C to communicate, 2 pins are required to interface. + + Adafruit invests time and resources providing this open source code, + please support Adafruit andopen-source hardware by purchasing products + from Adafruit! + + Written by Kevin Townsend for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ***************************************************************************/ +#ifndef __ADAFRUIT_10DOF_H__ +#define __ADAFRUIT_10DOF_H__ + +#include "Adafruit_Sensor.h" +//#include <Adafruit_Sensor.h> +//#include <Adafruit_LSM303_U.h> +//#include <Adafruit_BMP085_U.h> +//#include <Adafruit_L3GD20_U.h> + + +/** Sensor axis */ +typedef enum +{ + SENSOR_AXIS_X = (1), + SENSOR_AXIS_Y = (2), + SENSOR_AXIS_Z = (3) +} sensors_axis_t; + +/* Driver for the the 10DOF breakout sensors */ +class Adafruit_10DOF +{ + public: + Adafruit_10DOF(void); + bool begin(void); + + bool accelGetOrientation ( sensors_event_t *event, sensors_vec_t *orientation ); + bool magTiltCompensation ( sensors_axis_t axis, sensors_event_t *mag_event, sensors_event_t *accel_event ); + bool magGetOrientation ( sensors_axis_t axis, sensors_event_t *event, sensors_vec_t *mag_orientation ); + bool fusionGetOrientation ( sensors_event_t *accel_event, sensors_event_t *mag_event, sensors_vec_t *orientation ); + + private: +}; + +#endif
diff -r eae1575da9ca -r 5d102be2566c Adafruit_10DOF/Adafruit_BMP085_U.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Adafruit_10DOF/Adafruit_BMP085_U.cpp Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,467 @@ +/*************************************************************************** + This is a library for the BMP085 pressure sensor + + Designed specifically to work with the Adafruit BMP085 or BMP180 Breakout + ----> http://www.adafruit.com/products/391 + ----> http://www.adafruit.com/products/1603 + + These displays use I2C to communicate, 2 pins are required to interface. + + Adafruit invests time and resources providing this open source code, + please support Adafruit andopen-source hardware by purchasing products + from Adafruit! + + Written by Kevin Townsend for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ***************************************************************************/ + +//#include "mbed.h" +//#include "I2C.h" +#include "Adafruit_BMP085_U.h" + +static bmp085_calib_data _bmp085_coeffs; // Last read accelerometer data will be available here +static uint8_t _bmp085Mode; + +#define BMP085_USE_DATASHEET_VALS (0) /* Set to 1 for sanity check */ +typedef uint8_t byte; + +//extern i2c; +//extern I2C* i2c; +//extern mbed::I2C* i2c; +//extern mbed::I2C* i2c(I2C_SDA, I2C_SCL); +//extern I2C i2c(); +//extern i2c(I2C_SDA, I2C_SCL); +//extern int i2c(I2C_SDA, I2C_SCL); +//extern I2C i2c(I2C_SDA, I2C_SCL); // sda, scl + +/*************************************************************************** + PRIVATE FUNCTIONS + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Writes an 8 bit value over I2C +*/ +/**************************************************************************/ +static void writeCommand(byte reg, byte value) +{ + char data_write[2]; + + data_write[0] = reg; + data_write[1] = value; + int status = i2c->write(BMP085_ADDRESS, data_write, 2, 0); + +} + +/**************************************************************************/ +/*! + @brief Reads an 8 bit value over I2C +*/ +/**************************************************************************/ +static void read8(byte reg, uint8_t *value) +{ + char data_write[2]; + char data_read[2]; + + // Read register + data_write[0] = reg; + i2c->write(BMP085_ADDRESS, data_write, 1, 1); // no stop + i2c->read(BMP085_ADDRESS, data_read, 2, 0); + +} + +/**************************************************************************/ +/*! + @brief Reads a 16 bit value over I2C +*/ +/**************************************************************************/ +static void read16(byte reg, uint16_t *value) +{ + char data_write[2]; + char data_read[2]; + //uint8_t data_read[2]; + + //Sample_RIIC_Read( (uint8_t)BMP085_ADDRESS,reg,1, data_read); + data_write[0] = reg; + i2c->write(BMP085_ADDRESS, data_write, 1, 1); // no stop + i2c->read(BMP085_ADDRESS, data_read, 2, 0); + + *value = (((uint16_t)data_read[0]) << 8) | ((uint16_t)data_read[1]); + +} + +/**************************************************************************/ +/*! + @brief Reads a signed 16 bit value over I2C +*/ +/**************************************************************************/ +static void readS16(byte reg, int16_t *value) +{ + uint16_t i; + read16(reg, &i); + *value = (int16_t)i; +} + +/**************************************************************************/ +/*! + @brief Reads the factory-set coefficients +*/ +/**************************************************************************/ +static void readCoefficients(void) +{ + #if BMP085_USE_DATASHEET_VALS + _bmp085_coeffs.ac1 = 408; + _bmp085_coeffs.ac2 = -72; + _bmp085_coeffs.ac3 = -14383; + _bmp085_coeffs.ac4 = 32741; + _bmp085_coeffs.ac5 = 32757; + _bmp085_coeffs.ac6 = 23153; + _bmp085_coeffs.b1 = 6190; + _bmp085_coeffs.b2 = 4; + _bmp085_coeffs.mb = -32768; + _bmp085_coeffs.mc = -8711; + _bmp085_coeffs.md = 2868; + _bmp085Mode = 0; + #else + readS16(BMP085_REGISTER_CAL_AC1, &_bmp085_coeffs.ac1); + readS16(BMP085_REGISTER_CAL_AC2, &_bmp085_coeffs.ac2); + readS16(BMP085_REGISTER_CAL_AC3, &_bmp085_coeffs.ac3); + read16(BMP085_REGISTER_CAL_AC4, &_bmp085_coeffs.ac4); + read16(BMP085_REGISTER_CAL_AC5, &_bmp085_coeffs.ac5); + read16(BMP085_REGISTER_CAL_AC6, &_bmp085_coeffs.ac6); + readS16(BMP085_REGISTER_CAL_B1, &_bmp085_coeffs.b1); + readS16(BMP085_REGISTER_CAL_B2, &_bmp085_coeffs.b2); + readS16(BMP085_REGISTER_CAL_MB, &_bmp085_coeffs.mb); + readS16(BMP085_REGISTER_CAL_MC, &_bmp085_coeffs.mc); + readS16(BMP085_REGISTER_CAL_MD, &_bmp085_coeffs.md); + #endif +} + +/**************************************************************************/ +/*! + +*/ +/**************************************************************************/ +static void readRawTemperature(int32_t *temperature) +{ + #if BMP085_USE_DATASHEET_VALS + *temperature = 27898; + #else + uint16_t t; + writeCommand(BMP085_REGISTER_CONTROL, BMP085_REGISTER_READTEMPCMD); + wait(5);//delay(5); + read16(BMP085_REGISTER_TEMPDATA, &t); + *temperature = t; + #endif +} + +/**************************************************************************/ +/*! + +*/ +/**************************************************************************/ +static void readRawPressure(int32_t *pressure) +{ + #if BMP085_USE_DATASHEET_VALS + *pressure = 23843; + #else + uint8_t p8; + uint16_t p16; + int32_t p32; + + writeCommand(BMP085_REGISTER_CONTROL, BMP085_REGISTER_READPRESSURECMD + (_bmp085Mode << 6)); + switch(_bmp085Mode) + { + case BMP085_MODE_ULTRALOWPOWER: + wait(5);//delay(5); + break; + case BMP085_MODE_STANDARD: + wait(8);//delay(8); + break; + case BMP085_MODE_HIGHRES: + wait(14);//delay(14); + break; + case BMP085_MODE_ULTRAHIGHRES: + default: + wait(26);//delay(26); + break; + } + + read16(BMP085_REGISTER_PRESSUREDATA, &p16); + p32 = (uint32_t)p16 << 8; + read8(BMP085_REGISTER_PRESSUREDATA+2, &p8); + p32 += p8; + p32 >>= (8 - _bmp085Mode); + + *pressure = p32; + #endif +} + +/**************************************************************************/ +/*! + @brief Compute B5 coefficient used in temperature & pressure calcs. +*/ +/**************************************************************************/ +int32_t Adafruit_BMP085_Unified::computeB5(int32_t ut) { + int32_t X1 = (ut - (int32_t)_bmp085_coeffs.ac6) * ((int32_t)_bmp085_coeffs.ac5) >> 15; + int32_t X2 = ((int32_t)_bmp085_coeffs.mc << 11) / (X1+(int32_t)_bmp085_coeffs.md); + return X1 + X2; +} + + +/*************************************************************************** + CONSTRUCTOR + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Instantiates a new Adafruit_BMP085_Unified class +*/ +/**************************************************************************/ +Adafruit_BMP085_Unified::Adafruit_BMP085_Unified(int32_t sensorID) { + _sensorID = sensorID; +} + +/*************************************************************************** + PUBLIC FUNCTIONS + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Setups the HW +*/ +/**************************************************************************/ +bool Adafruit_BMP085_Unified::begin(bmp085_mode_t mode) +{ + // Enable I2C + //Wire.begin(); + + /* Mode boundary check */ + if ((mode > BMP085_MODE_ULTRAHIGHRES) || (mode < 0)) + { + mode = BMP085_MODE_ULTRAHIGHRES; + } + + /* Make sure we have the right device */ + uint8_t id; + read8(BMP085_REGISTER_CHIPID, &id); + if(id != 0x55) + { + return false; + } + + /* Set the mode indicator */ + _bmp085Mode = mode; + + /* Coefficients need to be read once */ + readCoefficients(); + + return true; +} + +/**************************************************************************/ +/*! + @brief Gets the compensated pressure level in kPa +*/ +/**************************************************************************/ +void Adafruit_BMP085_Unified::getPressure(float *pressure) +{ + int32_t ut = 0, up = 0, compp = 0; + int32_t x1, x2, b5, b6, x3, b3, p; + uint32_t b4, b7; + + /* Get the raw pressure and temperature values */ + readRawTemperature(&ut); + readRawPressure(&up); + + /* Temperature compensation */ + b5 = computeB5(ut); + + /* Pressure compensation */ + b6 = b5 - 4000; + x1 = (_bmp085_coeffs.b2 * ((b6 * b6) >> 12)) >> 11; + x2 = (_bmp085_coeffs.ac2 * b6) >> 11; + x3 = x1 + x2; + b3 = (((((int32_t) _bmp085_coeffs.ac1) * 4 + x3) << _bmp085Mode) + 2) >> 2; + x1 = (_bmp085_coeffs.ac3 * b6) >> 13; + x2 = (_bmp085_coeffs.b1 * ((b6 * b6) >> 12)) >> 16; + x3 = ((x1 + x2) + 2) >> 2; + b4 = (_bmp085_coeffs.ac4 * (uint32_t) (x3 + 32768)) >> 15; + b7 = ((uint32_t) (up - b3) * (50000 >> _bmp085Mode)); + + if (b7 < 0x80000000) + { + p = (b7 << 1) / b4; + } + else + { + p = (b7 / b4) << 1; + } + + x1 = (p >> 8) * (p >> 8); + x1 = (x1 * 3038) >> 16; + x2 = (-7357 * p) >> 16; + compp = p + ((x1 + x2 + 3791) >> 4); + + /* Assign compensated pressure value */ + *pressure = compp; +} + +/**************************************************************************/ +/*! + @brief Reads the temperatures in degrees Celsius +*/ +/**************************************************************************/ +void Adafruit_BMP085_Unified::getTemperature(float *temp) +{ + int32_t UT, X1, X2, B5; // following ds convention + float t; + + readRawTemperature(&UT); + + #if BMP085_USE_DATASHEET_VALS + // use datasheet numbers! + UT = 27898; + _bmp085_coeffs.ac6 = 23153; + _bmp085_coeffs.ac5 = 32757; + _bmp085_coeffs.mc = -8711; + _bmp085_coeffs.md = 2868; + #endif + + B5 = computeB5(UT); + t = (B5+8) >> 4; + t /= 10; + + *temp = t; +} + +/**************************************************************************/ +/*! + Calculates the altitude (in meters) from the specified atmospheric + pressure (in hPa), and sea-level pressure (in hPa). + + @param seaLevel Sea-level pressure in hPa + @param atmospheric Atmospheric pressure in hPa +*/ +/**************************************************************************/ +float Adafruit_BMP085_Unified::pressureToAltitude(float seaLevel, float atmospheric) +{ + // Equation taken from BMP180 datasheet (page 16): + // http://www.adafruit.com/datasheets/BST-BMP180-DS000-09.pdf + + // Note that using the equation from wikipedia can give bad results + // at high altitude. See this thread for more information: + // http://forums.adafruit.com/viewtopic.php?f=22&t=58064 + float y = 0.1903; + float x; + x = atmospheric / seaLevel; + + return 44330.0 * (1.0 - pow(x, y)); // 0.1903)); +} + +/**************************************************************************/ +/*! + Calculates the altitude (in meters) from the specified atmospheric + pressure (in hPa), and sea-level pressure (in hPa). Note that this + function just calls the overload of pressureToAltitude which takes + seaLevel and atmospheric pressure--temperature is ignored. The original + implementation of this function was based on calculations from Wikipedia + which are not accurate at higher altitudes. To keep compatibility with + old code this function remains with the same interface, but it calls the + more accurate calculation. + + @param seaLevel Sea-level pressure in hPa + @param atmospheric Atmospheric pressure in hPa + @param temp Temperature in degrees Celsius +*/ +/**************************************************************************/ +float Adafruit_BMP085_Unified::pressureToAltitude(float seaLevel, float atmospheric, float temp) +{ + return pressureToAltitude(seaLevel, atmospheric); +} + +/**************************************************************************/ +/*! + Calculates the pressure at sea level (in hPa) from the specified altitude + (in meters), and atmospheric pressure (in hPa). + + @param altitude Altitude in meters + @param atmospheric Atmospheric pressure in hPa +*/ +/**************************************************************************/ +float Adafruit_BMP085_Unified::seaLevelForAltitude(float altitude, float atmospheric) +{ + // Equation taken from BMP180 datasheet (page 17): + // http://www.adafruit.com/datasheets/BST-BMP180-DS000-09.pdf + + // Note that using the equation from wikipedia can give bad results + // at high altitude. See this thread for more information: + // http://forums.adafruit.com/viewtopic.php?f=22&t=58064 + + return atmospheric / pow(1.0 - (altitude/44330.0), 5.255); +} + +/**************************************************************************/ +/*! + Calculates the pressure at sea level (in hPa) from the specified altitude + (in meters), and atmospheric pressure (in hPa). Note that this + function just calls the overload of seaLevelForAltitude which takes + altitude and atmospheric pressure--temperature is ignored. The original + implementation of this function was based on calculations from Wikipedia + which are not accurate at higher altitudes. To keep compatibility with + old code this function remains with the same interface, but it calls the + more accurate calculation. + + @param altitude Altitude in meters + @param atmospheric Atmospheric pressure in hPa + @param temp Temperature in degrees Celsius +*/ +/**************************************************************************/ +float Adafruit_BMP085_Unified::seaLevelForAltitude(float altitude, float atmospheric, float temp) +{ + return seaLevelForAltitude(altitude, atmospheric); +} + +/**************************************************************************/ +/*! + @brief Provides the sensor_t data for this sensor +*/ +/**************************************************************************/ +void Adafruit_BMP085_Unified::getSensor(sensor_t *sensor) +{ + /* Clear the sensor_t object */ + memset(sensor, 0, sizeof(sensor_t)); + + /* Insert the sensor name in the fixed length char array */ + strncpy (sensor->name, "BMP085", sizeof(sensor->name) - 1); + sensor->name[sizeof(sensor->name)- 1] = 0; + sensor->version = 1; + sensor->sensor_id = _sensorID; + sensor->type = SENSOR_TYPE_PRESSURE; + sensor->min_delay = 0; + sensor->max_value = 1100.0F; // 300..1100 hPa + sensor->min_value = 300.0F; + sensor->resolution = 0.01F; // Datasheet states 0.01 hPa resolution +} + +/**************************************************************************/ +/*! + @brief Reads the sensor and returns the data as a sensors_event_t +*/ +/**************************************************************************/ +bool Adafruit_BMP085_Unified::getEvent(sensors_event_t *event) +{ + float pressure_kPa; + + /* Clear the event */ + memset(event, 0, sizeof(sensors_event_t)); + + event->version = sizeof(sensors_event_t); + event->sensor_id = _sensorID; + event->type = SENSOR_TYPE_PRESSURE; + event->timestamp = 0; + getPressure(&pressure_kPa); + event->pressure = pressure_kPa / 100.0F; + + return true; +}
diff -r eae1575da9ca -r 5d102be2566c Adafruit_10DOF/Adafruit_BMP085_U.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Adafruit_10DOF/Adafruit_BMP085_U.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,109 @@ +/*************************************************************************** + This is a library for the BMP085 pressure sensor + + Designed specifically to work with the Adafruit BMP085 or BMP180 Breakout + ----> http://www.adafruit.com/products/391 + ----> http://www.adafruit.com/products/1603 + + These displays use I2C to communicate, 2 pins are required to interface. + + Adafruit invests time and resources providing this open source code, + please support Adafruit andopen-source hardware by purchasing products + from Adafruit! + + Written by Kevin Townsend for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ***************************************************************************/ +#ifndef __BMP085_H__ +#define __BMP085_H__ + +#include <Adafruit_Sensor.h> + +/*========================================================================= + I2C ADDRESS/BITS + -----------------------------------------------------------------------*/ + #define BMP085_ADDRESS (0xEE) +/*=========================================================================*/ + +/*========================================================================= + REGISTERS + -----------------------------------------------------------------------*/ + enum + { + BMP085_REGISTER_CAL_AC1 = 0xAA, // R Calibration data (16 bits) + BMP085_REGISTER_CAL_AC2 = 0xAC, // R Calibration data (16 bits) + BMP085_REGISTER_CAL_AC3 = 0xAE, // R Calibration data (16 bits) + BMP085_REGISTER_CAL_AC4 = 0xB0, // R Calibration data (16 bits) + BMP085_REGISTER_CAL_AC5 = 0xB2, // R Calibration data (16 bits) + BMP085_REGISTER_CAL_AC6 = 0xB4, // R Calibration data (16 bits) + BMP085_REGISTER_CAL_B1 = 0xB6, // R Calibration data (16 bits) + BMP085_REGISTER_CAL_B2 = 0xB8, // R Calibration data (16 bits) + BMP085_REGISTER_CAL_MB = 0xBA, // R Calibration data (16 bits) + BMP085_REGISTER_CAL_MC = 0xBC, // R Calibration data (16 bits) + BMP085_REGISTER_CAL_MD = 0xBE, // R Calibration data (16 bits) + BMP085_REGISTER_CHIPID = 0xD0, + BMP085_REGISTER_VERSION = 0xD1, + BMP085_REGISTER_SOFTRESET = 0xE0, + BMP085_REGISTER_CONTROL = 0xF4, + BMP085_REGISTER_TEMPDATA = 0xF6, + BMP085_REGISTER_PRESSUREDATA = 0xF6, + BMP085_REGISTER_READTEMPCMD = 0x2E, + BMP085_REGISTER_READPRESSURECMD = 0x34 + }; +/*=========================================================================*/ + +/*========================================================================= + MODE SETTINGS + -----------------------------------------------------------------------*/ + typedef enum + { + BMP085_MODE_ULTRALOWPOWER = 0, + BMP085_MODE_STANDARD = 1, + BMP085_MODE_HIGHRES = 2, + BMP085_MODE_ULTRAHIGHRES = 3 + } bmp085_mode_t; +/*=========================================================================*/ + +/*========================================================================= + CALIBRATION DATA + -----------------------------------------------------------------------*/ + typedef struct + { + int16_t ac1; + int16_t ac2; + int16_t ac3; + uint16_t ac4; + uint16_t ac5; + uint16_t ac6; + int16_t b1; + int16_t b2; + int16_t mb; + int16_t mc; + int16_t md; + } bmp085_calib_data; +/*=========================================================================*/ + +class Adafruit_BMP085_Unified// : public Adafruit_Sensor +{ + public: + Adafruit_BMP085_Unified(int32_t sensorID = -1); + + bool begin(bmp085_mode_t mode = BMP085_MODE_ULTRAHIGHRES); + void getTemperature(float *temp); + void getPressure(float *pressure); + float pressureToAltitude(float seaLvel, float atmospheric); + float seaLevelForAltitude(float altitude, float atmospheric); + // Note that the next two functions are just for compatibility with old + // code that passed the temperature as a third parameter. A newer + // calculation is used which does not need temperature. + float pressureToAltitude(float seaLevel, float atmospheric, float temp); + float seaLevelForAltitude(float altitude, float atmospheric, float temp); + bool getEvent(sensors_event_t*); + void getSensor(sensor_t*); + + private: + int32_t computeB5(int32_t ut); + int32_t _sensorID; +}; + +#endif
diff -r eae1575da9ca -r 5d102be2566c Adafruit_10DOF/Adafruit_L3GD20_U.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Adafruit_10DOF/Adafruit_L3GD20_U.cpp Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,354 @@ +/*************************************************** + This is a library for the L3GD20 GYROSCOPE + + Designed specifically to work with the Adafruit L3GD20 Breakout + ----> https://www.adafruit.com/products/1032 + + These sensors use I2C or SPI to communicate, 2 pins (I2C) + or 4 pins (SPI) are required to interface. + + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + Written by Kevin "KTOWN" Townsend for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ****************************************************/ + +#include "Adafruit_L3GD20_U.h" + + +//Timer timer; + +//extern I2C i2c(I2C_SDA, I2C_SCL); // sda, scl + +/*************************************************************************** + PRIVATE FUNCTIONS + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Abstract away platform differences in Arduino wire library +*/ +/**************************************************************************/ +void Adafruit_L3GD20_Unified::write8(byte reg, byte value) +{ + char data_write[2]; + + data_write[0] = reg; + data_write[1] = value; + int status = i2c->write(L3GD20_ADDRESS, data_write, 2, 0); + +} + +/**************************************************************************/ +/*! + @brief Abstract away platform differences in Arduino wire library +*/ +/**************************************************************************/ +byte Adafruit_L3GD20_Unified::read8(byte reg) +{ + byte value; + + + char data_write[2]; + char data_read[2]; + + + // Read register + data_write[0] = reg; + i2c->write(L3GD20_ADDRESS, data_write, 1, 1); // no stop + i2c->read(L3GD20_ADDRESS, data_read, 2, 0); + value = data_read[0]; + + return value; +} + +/*************************************************************************** + CONSTRUCTOR + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Instantiates a new Adafruit_L3GD20_Unified class +*/ +/**************************************************************************/ +Adafruit_L3GD20_Unified::Adafruit_L3GD20_Unified(int32_t sensorID) { + _sensorID = sensorID; + _autoRangeEnabled = false; +} + +/*************************************************************************** + PUBLIC FUNCTIONS + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Setups the HW +*/ +/**************************************************************************/ +bool Adafruit_L3GD20_Unified::begin(gyroRange_t rng) +{ + + /* Set the range the an appropriate value */ + _range = rng; + + /* Make sure we have the correct chip ID since this checks + for correct address and that the IC is properly connected */ + uint8_t id = read8(GYRO_REGISTER_WHO_AM_I); + //Serial.println(id, HEX); + if ((id != L3GD20_ID) && (id != L3GD20H_ID)) + { + return false; + } + + /* Set CTRL_REG1 (0x20) + ==================================================================== + BIT Symbol Description Default + --- ------ --------------------------------------------- ------- + 7-6 DR1/0 Output data rate 00 + 5-4 BW1/0 Bandwidth selection 00 + 3 PD 0 = Power-down mode, 1 = normal/sleep mode 0 + 2 ZEN Z-axis enable (0 = disabled, 1 = enabled) 1 + 1 YEN Y-axis enable (0 = disabled, 1 = enabled) 1 + 0 XEN X-axis enable (0 = disabled, 1 = enabled) 1 */ + + /* Reset then switch to normal mode and enable all three channels */ + write8(GYRO_REGISTER_CTRL_REG1, 0x00); + write8(GYRO_REGISTER_CTRL_REG1, 0x0F); + /* ------------------------------------------------------------------ */ + + /* Set CTRL_REG2 (0x21) + ==================================================================== + BIT Symbol Description Default + --- ------ --------------------------------------------- ------- + 5-4 HPM1/0 High-pass filter mode selection 00 + 3-0 HPCF3..0 High-pass filter cutoff frequency selection 0000 */ + + /* Nothing to do ... keep default values */ + /* ------------------------------------------------------------------ */ + + /* Set CTRL_REG3 (0x22) + ==================================================================== + BIT Symbol Description Default + --- ------ --------------------------------------------- ------- + 7 I1_Int1 Interrupt enable on INT1 (0=disable,1=enable) 0 + 6 I1_Boot Boot status on INT1 (0=disable,1=enable) 0 + 5 H-Lactive Interrupt active config on INT1 (0=high,1=low) 0 + 4 PP_OD Push-Pull/Open-Drain (0=PP, 1=OD) 0 + 3 I2_DRDY Data ready on DRDY/INT2 (0=disable,1=enable) 0 + 2 I2_WTM FIFO wtrmrk int on DRDY/INT2 (0=dsbl,1=enbl) 0 + 1 I2_ORun FIFO overrun int on DRDY/INT2 (0=dsbl,1=enbl) 0 + 0 I2_Empty FIFI empty int on DRDY/INT2 (0=dsbl,1=enbl) 0 */ + + /* Nothing to do ... keep default values */ + /* ------------------------------------------------------------------ */ + + /* Set CTRL_REG4 (0x23) + ==================================================================== + BIT Symbol Description Default + --- ------ --------------------------------------------- ------- + 7 BDU Block Data Update (0=continuous, 1=LSB/MSB) 0 + 6 BLE Big/Little-Endian (0=Data LSB, 1=Data MSB) 0 + 5-4 FS1/0 Full scale selection 00 + 00 = 250 dps + 01 = 500 dps + 10 = 2000 dps + 11 = 2000 dps + 0 SIM SPI Mode (0=4-wire, 1=3-wire) 0 */ + + /* Adjust resolution if requested */ + switch(_range) + { + case GYRO_RANGE_250DPS: + write8(GYRO_REGISTER_CTRL_REG4, 0x00); + break; + case GYRO_RANGE_500DPS: + write8(GYRO_REGISTER_CTRL_REG4, 0x10); + break; + case GYRO_RANGE_2000DPS: + write8(GYRO_REGISTER_CTRL_REG4, 0x20); + break; + } + /* ------------------------------------------------------------------ */ + + /* Set CTRL_REG5 (0x24) + ==================================================================== + BIT Symbol Description Default + --- ------ --------------------------------------------- ------- + 7 BOOT Reboot memory content (0=normal, 1=reboot) 0 + 6 FIFO_EN FIFO enable (0=FIFO disable, 1=enable) 0 + 4 HPen High-pass filter enable (0=disable,1=enable) 0 + 3-2 INT1_SEL INT1 Selection config 00 + 1-0 OUT_SEL Out selection config 00 */ + + /* Nothing to do ... keep default values */ + /* ------------------------------------------------------------------ */ + + return true; +} + +/**************************************************************************/ +/*! + @brief Enables or disables auto-ranging +*/ +/**************************************************************************/ +void Adafruit_L3GD20_Unified::enableAutoRange(bool enabled) +{ + _autoRangeEnabled = enabled; +} + +/**************************************************************************/ +/*! + @brief Gets the most recent sensor event +*/ +/**************************************************************************/ +bool Adafruit_L3GD20_Unified::getEvent(sensors_event_t* event) +{ + char data_write[2]; + char data_read[6]; + uint32_t status; + uint8_t xhi; + uint8_t xlo; + uint8_t zhi; + uint8_t zlo; + uint8_t yhi; + uint8_t ylo; + + bool readingValid = false; + + /* Clear the event */ + memset(event, 0, sizeof(sensors_event_t)); + + event->version = sizeof(sensors_event_t); + event->sensor_id = _sensorID; + event->type = SENSOR_TYPE_GYROSCOPE; + + while(!readingValid) + { + event->timestamp = timer.read_ms();//millis(); + + // Read 6 bytes from the sensor + //status = Sample_RIIC_Read(L3GD20_ADDRESS,GYRO_REGISTER_OUT_X_L | 0x80,6,data_read); + data_write[0] = GYRO_REGISTER_OUT_X_L | 0x80 ; + i2c->write(L3GD20_ADDRESS, data_write, 1, 1);// non stop i2c + + // Read the accelerometer + // Read 6 byte data + //status = i2c->read(L3GD20_ADDRESS, data_read, 6, 0); + status = i2c->read(L3GD20_ADDRESS, data_read, 6, 0); + // Read the accelerometer + + // Wait around until enough data is available + + if ( status == 0 ) + { + xlo = data_read[0]; + xhi = data_read[1]; + ylo = data_read[2]; + yhi = data_read[3]; + zlo = data_read[4]; + zhi = data_read[5]; + } + /* Shift values to create properly formed integer (low byte first) */ + event->gyro.x = (int16_t)(xlo | (xhi << 8)); + event->gyro.y = (int16_t)(ylo | (yhi << 8)); + event->gyro.z = (int16_t)(zlo | (zhi << 8)); + + /* Make sure the sensor isn't saturating if auto-ranging is enabled */ + if (!_autoRangeEnabled) + { + readingValid = true; + } + else + { + /* Check if the sensor is saturating or not */ + if ( (event->gyro.x >= 32760) | (event->gyro.x <= -32760) | + (event->gyro.y >= 32760) | (event->gyro.y <= -32760) | + (event->gyro.z >= 32760) | (event->gyro.z <= -32760) ) + { + /* Saturating .... increase the range if we can */ + switch(_range) + { + case GYRO_RANGE_500DPS: + /* Push the range up to 2000dps */ + _range = GYRO_RANGE_2000DPS; + write8(GYRO_REGISTER_CTRL_REG1, 0x00); + write8(GYRO_REGISTER_CTRL_REG1, 0x0F); + write8(GYRO_REGISTER_CTRL_REG4, 0x20); + write8(GYRO_REGISTER_CTRL_REG5, 0x80); + readingValid = false; + // Serial.println("Changing range to 2000DPS"); + break; + case GYRO_RANGE_250DPS: + /* Push the range up to 500dps */ + _range = GYRO_RANGE_500DPS; + write8(GYRO_REGISTER_CTRL_REG1, 0x00); + write8(GYRO_REGISTER_CTRL_REG1, 0x0F); + write8(GYRO_REGISTER_CTRL_REG4, 0x10); + write8(GYRO_REGISTER_CTRL_REG5, 0x80); + readingValid = false; + // Serial.println("Changing range to 500DPS"); + break; + default: + readingValid = true; + break; + } + } + else + { + /* All values are withing range */ + readingValid = true; + } + } + } + + /* Compensate values depending on the resolution */ + switch(_range) + { + case GYRO_RANGE_250DPS: + event->gyro.x *= GYRO_SENSITIVITY_250DPS; + event->gyro.y *= GYRO_SENSITIVITY_250DPS; + event->gyro.z *= GYRO_SENSITIVITY_250DPS; + break; + case GYRO_RANGE_500DPS: + event->gyro.x *= GYRO_SENSITIVITY_500DPS; + event->gyro.y *= GYRO_SENSITIVITY_500DPS; + event->gyro.z *= GYRO_SENSITIVITY_500DPS; + break; + case GYRO_RANGE_2000DPS: + event->gyro.x *= GYRO_SENSITIVITY_2000DPS; + event->gyro.y *= GYRO_SENSITIVITY_2000DPS; + event->gyro.z *= GYRO_SENSITIVITY_2000DPS; + break; + } + + /* Convert values to rad/s */ + event->gyro.x *= SENSORS_DPS_TO_RADS; + event->gyro.y *= SENSORS_DPS_TO_RADS; + event->gyro.z *= SENSORS_DPS_TO_RADS; + + return true; +} + +/**************************************************************************/ +/*! + @brief Gets the sensor_t data +*/ +/**************************************************************************/ +void Adafruit_L3GD20_Unified::getSensor(sensor_t* sensor) +{ + /* Clear the sensor_t object */ + memset(sensor, 0, sizeof(sensor_t)); + + /* Insert the sensor name in the fixed length char array */ + strncpy (sensor->name, "L3GD20", sizeof(sensor->name) - 1); + sensor->name[sizeof(sensor->name)- 1] = 0; + sensor->version = 1; + sensor->sensor_id = _sensorID; + sensor->type = SENSOR_TYPE_GYROSCOPE; + sensor->min_delay = 0; + sensor->max_value = (float)this->_range * SENSORS_DPS_TO_RADS; + sensor->min_value = (this->_range * -1.0) * SENSORS_DPS_TO_RADS; + sensor->resolution = 0.0F; // TBD +}
diff -r eae1575da9ca -r 5d102be2566c Adafruit_10DOF/Adafruit_L3GD20_U.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Adafruit_10DOF/Adafruit_L3GD20_U.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,100 @@ +/*************************************************** + This is a library for the L3GD20 GYROSCOPE + + Designed specifically to work with the Adafruit L3GD20 Breakout + ----> https://www.adafruit.com/products/1032 + + These sensors use I2C or SPI to communicate, 2 pins (I2C) + or 4 pins (SPI) are required to interface. + + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + Written by Kevin "KTOWN" Townsend for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ****************************************************/ +#ifndef __L3GD20_H__ +#define __L3GD20_H__ + +#include <Adafruit_Sensor.h> + +/*========================================================================= + I2C ADDRESS/BITS AND SETTINGS + -----------------------------------------------------------------------*/ + #define L3GD20_ADDRESS (0xD6) // 1101011x x=R/w + #define L3GD20_WRITE (0x00) // Bit write + #define L3GD20_READ (0x01) // Bit read + #define L3GD20_POLL_TIMEOUT (100) // Maximum number of read attempts + #define L3GD20_ID 0xD4 + #define L3GD20H_ID 0xD7 + #define GYRO_SENSITIVITY_250DPS (0.00875F) // Roughly 22/256 for fixed point match + #define GYRO_SENSITIVITY_500DPS (0.0175F) // Roughly 45/256 + #define GYRO_SENSITIVITY_2000DPS (0.070F) // Roughly 18/256 +/*=========================================================================*/ + +/*========================================================================= + REGISTERS + -----------------------------------------------------------------------*/ + typedef enum + { // DEFAULT TYPE + GYRO_REGISTER_WHO_AM_I = 0x0F, // 11010100 r + GYRO_REGISTER_CTRL_REG1 = 0x20, // 00000111 rw + GYRO_REGISTER_CTRL_REG2 = 0x21, // 00000000 rw + GYRO_REGISTER_CTRL_REG3 = 0x22, // 00000000 rw + GYRO_REGISTER_CTRL_REG4 = 0x23, // 00000000 rw + GYRO_REGISTER_CTRL_REG5 = 0x24, // 00000000 rw + GYRO_REGISTER_REFERENCE = 0x25, // 00000000 rw + GYRO_REGISTER_OUT_TEMP = 0x26, // r + GYRO_REGISTER_STATUS_REG = 0x27, // r + GYRO_REGISTER_OUT_X_L = 0x28, // r + GYRO_REGISTER_OUT_X_H = 0x29, // r + GYRO_REGISTER_OUT_Y_L = 0x2A, // r + GYRO_REGISTER_OUT_Y_H = 0x2B, // r + GYRO_REGISTER_OUT_Z_L = 0x2C, // r + GYRO_REGISTER_OUT_Z_H = 0x2D, // r + GYRO_REGISTER_FIFO_CTRL_REG = 0x2E, // 00000000 rw + GYRO_REGISTER_FIFO_SRC_REG = 0x2F, // r + GYRO_REGISTER_INT1_CFG = 0x30, // 00000000 rw + GYRO_REGISTER_INT1_SRC = 0x31, // r + GYRO_REGISTER_TSH_XH = 0x32, // 00000000 rw + GYRO_REGISTER_TSH_XL = 0x33, // 00000000 rw + GYRO_REGISTER_TSH_YH = 0x34, // 00000000 rw + GYRO_REGISTER_TSH_YL = 0x35, // 00000000 rw + GYRO_REGISTER_TSH_ZH = 0x36, // 00000000 rw + GYRO_REGISTER_TSH_ZL = 0x37, // 00000000 rw + GYRO_REGISTER_INT1_DURATION = 0x38 // 00000000 rw + } gyroRegisters_t; +/*=========================================================================*/ + +/*========================================================================= + OPTIONAL SPEED SETTINGS + -----------------------------------------------------------------------*/ + typedef enum + { + GYRO_RANGE_250DPS = 250, + GYRO_RANGE_500DPS = 500, + GYRO_RANGE_2000DPS = 2000 + } gyroRange_t; +/*=========================================================================*/ + +class Adafruit_L3GD20_Unified //: public Adafruit_Sensor +{ + public: + Adafruit_L3GD20_Unified(int32_t sensorID = -1); + + bool begin ( gyroRange_t rng = GYRO_RANGE_250DPS ); + void enableAutoRange ( bool enabled ); + bool getEvent ( sensors_event_t* ); + void getSensor ( sensor_t* ); + + private: + void write8 ( byte reg, byte value ); + uint8_t read8 ( byte reg ); + gyroRange_t _range; + int32_t _sensorID; + bool _autoRangeEnabled; +}; + +#endif +
diff -r eae1575da9ca -r 5d102be2566c Adafruit_10DOF/Adafruit_LSM303_U.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Adafruit_10DOF/Adafruit_LSM303_U.cpp Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,530 @@ +/*************************************************************************** + This is a library for the LSM303 Accelerometer and magnentometer/compass + + Designed specifically to work with the Adafruit LSM303DLHC Breakout + + These displays use I2C to communicate, 2 pins are required to interface. + + Adafruit invests time and resources providing this open source code, + please support Adafruit andopen-source hardware by purchasing products + from Adafruit! + + Written by Kevin Townsend for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ***************************************************************************/ + +#include "Adafruit_LSM303_U.h" + +//extern I2C i2c(I2C_SDA, I2C_SCL); // sda, scl + +/* enabling this #define will enable the debug print blocks +#define LSM303_DEBUG +*/ +typedef uint8_t byte; + +static float _lsm303Accel_MG_LSB = 0.001F; // 1, 2, 4 or 12 mg per lsb +static float _lsm303Mag_Gauss_LSB_XY = 1100.0F; // Varies with gain +static float _lsm303Mag_Gauss_LSB_Z = 980.0F; // Varies with gain + +/*************************************************************************** + ACCELEROMETER + ***************************************************************************/ +/*************************************************************************** + PRIVATE FUNCTIONS + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Abstract away platform differences in Arduino wire library +*/ +/**************************************************************************/ +void Adafruit_LSM303_Accel_Unified::write8(byte address, byte reg, byte value) +{ + char data_write[2]; + + data_write[0] = reg; + data_write[1] = value; + int status = i2c->write(address, data_write, 2, 0); + +} + +/**************************************************************************/ +/*! + @brief Abstract away platform differences in Arduino wire library +*/ +/**************************************************************************/ +byte Adafruit_LSM303_Accel_Unified::read8(byte address, byte reg) +{ + byte value; + + + char data_write[2]; + char data_read[2]; + + + // Read register + data_write[0] = reg; + i2c->write(address, data_write, 1, 1); // no stop + i2c->read(address, data_read, 2, 0); + value = data_read[0]; + + return value; +} + +/**************************************************************************/ +/*! + @brief Reads the raw data from the sensor +*/ +/**************************************************************************/ +void Adafruit_LSM303_Accel_Unified::read() +{ + char data_write[2]; + char data_read[6]; + uint32_t status; + uint8_t xlo; + uint8_t xhi; + uint8_t ylo; + uint8_t yhi; + uint8_t zlo; + uint8_t zhi; + + data_write[0] = LSM303_REGISTER_ACCEL_OUT_X_L_A | 0x80 ; + + i2c->write(LSM303_ADDRESS_ACCEL, data_write, 1, 1);// non stop i2c + + // Read the accelerometer + // Read 6 byte data + status = i2c->read(LSM303_ADDRESS_ACCEL, data_read, 6, 0); + // Read the accelerometer + + // Wait around until enough data is available + + if ( status == 0 ) + { + xlo = data_read[0]; + xhi = data_read[1]; + ylo = data_read[2]; + yhi = data_read[3]; + zlo = data_read[4]; + zhi = data_read[5]; + + + // Shift values to create properly formed integer (low byte first) + _accelData.x = (int16_t)(xlo | (xhi << 8)) >> 4; + _accelData.y = (int16_t)(ylo | (yhi << 8)) >> 4; + _accelData.z = (int16_t)(zlo | (zhi << 8)) >> 4; + } + +} + +/*************************************************************************** + CONSTRUCTOR + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Instantiates a new Adafruit_LSM303 class +*/ +/**************************************************************************/ +Adafruit_LSM303_Accel_Unified::Adafruit_LSM303_Accel_Unified(int32_t sensorID) { + _sensorID = sensorID; +} + +/*************************************************************************** + PUBLIC FUNCTIONS + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Setups the HW +*/ +/**************************************************************************/ +bool Adafruit_LSM303_Accel_Unified::begin() +{ + + // Enable the accelerometer (100Hz) + write8(LSM303_ADDRESS_ACCEL, LSM303_REGISTER_ACCEL_CTRL_REG1_A, 0x57); + + // LSM303DLHC has no WHOAMI register so read CTRL_REG1_A back to check + // if we are connected or not + uint8_t reg1_a = read8(LSM303_ADDRESS_ACCEL, LSM303_REGISTER_ACCEL_CTRL_REG1_A); + if (reg1_a != 0x57) + { + return false; + } + + return true; +} + +/**************************************************************************/ +/*! + @brief Gets the most recent sensor event +*/ +/**************************************************************************/ +bool Adafruit_LSM303_Accel_Unified::getEvent(sensors_event_t *event) { + /* Clear the event */ + memset(event, 0, sizeof(sensors_event_t)); + + /* Read new data */ + read(); + + event->version = sizeof(sensors_event_t); + event->sensor_id = _sensorID; + event->type = SENSOR_TYPE_ACCELEROMETER; + event->timestamp = timer.read_ms();//millis(); + event->acceleration.x = _accelData.x * _lsm303Accel_MG_LSB * SENSORS_GRAVITY_STANDARD; + event->acceleration.y = _accelData.y * _lsm303Accel_MG_LSB * SENSORS_GRAVITY_STANDARD; + event->acceleration.z = _accelData.z * _lsm303Accel_MG_LSB * SENSORS_GRAVITY_STANDARD; + + return true; +} + +/**************************************************************************/ +/*! + @brief Gets the sensor_t data +*/ +/**************************************************************************/ +void Adafruit_LSM303_Accel_Unified::getSensor(sensor_t *sensor) { + /* Clear the sensor_t object */ + memset(sensor, 0, sizeof(sensor_t)); + + /* Insert the sensor name in the fixed length char array */ + strncpy (sensor->name, "LSM303", sizeof(sensor->name) - 1); + sensor->name[sizeof(sensor->name)- 1] = 0; + sensor->version = 1; + sensor->sensor_id = _sensorID; + sensor->type = SENSOR_TYPE_ACCELEROMETER; + sensor->min_delay = 0; + sensor->max_value = 0.0F; // TBD + sensor->min_value = 0.0F; // TBD + sensor->resolution = 0.0F; // TBD +} + +/*************************************************************************** + MAGNETOMETER + ***************************************************************************/ +/*************************************************************************** + PRIVATE FUNCTIONS + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Abstract away platform differences in Arduino wire library +*/ +/**************************************************************************/ +void Adafruit_LSM303_Mag_Unified::write8(byte address, byte reg, byte value) +{ + char data_write[2]; + + data_write[0] = reg; + data_write[1] = value; + int status = i2c->write(address, data_write, 2, 0); + +} + +/**************************************************************************/ +/*! + @brief Abstract away platform differences in Arduino wire library +*/ +/**************************************************************************/ +byte Adafruit_LSM303_Mag_Unified::read8(byte address, byte reg) +{ + byte value; + + char data_write[2]; + char data_read[2]; + + // Read register + data_write[0] = reg; + i2c->write(address, data_write, 1, 1); // no stop + i2c->read(address, data_read, 2, 0); + value = data_read[0]; + + return value; +} + +/**************************************************************************/ +/*! + @brief Reads the raw data from the sensor +*/ +/**************************************************************************/ +void Adafruit_LSM303_Mag_Unified::read() +{ + + char data_write[2]; + char data_read[6]; + uint32_t status; + uint8_t xhi; + uint8_t xlo; + uint8_t zhi; + uint8_t zlo; + uint8_t yhi; + uint8_t ylo; + // Read the magnetometer + data_write[0] = LSM303_REGISTER_MAG_OUT_X_H_M ; + + i2c->write(LSM303_ADDRESS_MAG, data_write, 1, 1);// non stop i2c + + // Read the accelerometer + // Read 6 byte data + status = i2c->read(LSM303_ADDRESS_MAG, data_read, 6, 0); + // Read the accelerometer + + // Wait around until enough data is available + + if ( status == 0 ) + { + xlo = data_read[0]; + xhi = data_read[1]; + ylo = data_read[2]; + yhi = data_read[3]; + zlo = data_read[4]; + zhi = data_read[5]; + + + // Shift values to create properly formed integer (low byte first) + _magData.x = (int16_t)(xlo | ((int16_t)xhi << 8)); + _magData.y = (int16_t)(ylo | ((int16_t)yhi << 8)); + _magData.z = (int16_t)(zlo | ((int16_t)zhi << 8)); + } + // ToDo: Calculate orientation + // _magData.orientation = 0.0; +} + +/*************************************************************************** + CONSTRUCTOR + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Instantiates a new Adafruit_LSM303 class +*/ +/**************************************************************************/ +Adafruit_LSM303_Mag_Unified::Adafruit_LSM303_Mag_Unified(int32_t sensorID) { + _sensorID = sensorID; + _autoRangeEnabled = false; +} + +/*************************************************************************** + PUBLIC FUNCTIONS + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Setups the HW +*/ +/**************************************************************************/ +bool Adafruit_LSM303_Mag_Unified::begin() +{ + + // Enable the magnetometer + write8(LSM303_ADDRESS_MAG, LSM303_REGISTER_MAG_MR_REG_M, 0x00); + + // LSM303DLHC has no WHOAMI register so read CRA_REG_M to check + // the default value (0b00010000/0x10) + uint8_t reg1_a = read8(LSM303_ADDRESS_MAG, LSM303_REGISTER_MAG_CRA_REG_M); + if (reg1_a != 0x10) + { + return false; + } + + // Set the gain to a known level + setMagGain(LSM303_MAGGAIN_1_3); + + return true; +} + +/**************************************************************************/ +/*! + @brief Enables or disables auto-ranging +*/ +/**************************************************************************/ +void Adafruit_LSM303_Mag_Unified::enableAutoRange(bool enabled) +{ + _autoRangeEnabled = enabled; +} + +/**************************************************************************/ +/*! + @brief Sets the magnetometer's gain +*/ +/**************************************************************************/ +void Adafruit_LSM303_Mag_Unified::setMagGain(lsm303MagGain gain) +{ + write8(LSM303_ADDRESS_MAG, LSM303_REGISTER_MAG_CRB_REG_M, (byte)gain); + + _magGain = gain; + + switch(gain) + { + case LSM303_MAGGAIN_1_3: + _lsm303Mag_Gauss_LSB_XY = 1100; + _lsm303Mag_Gauss_LSB_Z = 980; + break; + case LSM303_MAGGAIN_1_9: + _lsm303Mag_Gauss_LSB_XY = 855; + _lsm303Mag_Gauss_LSB_Z = 760; + break; + case LSM303_MAGGAIN_2_5: + _lsm303Mag_Gauss_LSB_XY = 670; + _lsm303Mag_Gauss_LSB_Z = 600; + break; + case LSM303_MAGGAIN_4_0: + _lsm303Mag_Gauss_LSB_XY = 450; + _lsm303Mag_Gauss_LSB_Z = 400; + break; + case LSM303_MAGGAIN_4_7: + _lsm303Mag_Gauss_LSB_XY = 400; + _lsm303Mag_Gauss_LSB_Z = 355; + break; + case LSM303_MAGGAIN_5_6: + _lsm303Mag_Gauss_LSB_XY = 330; + _lsm303Mag_Gauss_LSB_Z = 295; + break; + case LSM303_MAGGAIN_8_1: + _lsm303Mag_Gauss_LSB_XY = 230; + _lsm303Mag_Gauss_LSB_Z = 205; + break; + } +} + +/**************************************************************************/ +/*! + @brief Sets the magnetometer's update rate +*/ +/**************************************************************************/ +void Adafruit_LSM303_Mag_Unified::setMagRate(lsm303MagRate rate) +{ + byte reg_m = ((byte)rate & 0x07) << 2; + write8(LSM303_ADDRESS_MAG, LSM303_REGISTER_MAG_CRA_REG_M, reg_m); +} + + +/**************************************************************************/ +/*! + @brief Gets the most recent sensor event +*/ +/**************************************************************************/ +bool Adafruit_LSM303_Mag_Unified::getEvent(sensors_event_t *event) { + bool readingValid = false; + + /* Clear the event */ + memset(event, 0, sizeof(sensors_event_t)); + + while(!readingValid) + { + + uint8_t reg_mg = read8(LSM303_ADDRESS_MAG, LSM303_REGISTER_MAG_SR_REG_Mg); + if (!(reg_mg & 0x1)) { + return false; + } + + /* Read new data */ + read(); + + /* Make sure the sensor isn't saturating if auto-ranging is enabled */ + if (!_autoRangeEnabled) + { + readingValid = true; + } + else + { +#ifdef LSM303_DEBUG + Serial.print(_magData.x); Serial.print(" "); + Serial.print(_magData.y); Serial.print(" "); + Serial.print(_magData.z); Serial.println(" "); +#endif + /* Check if the sensor is saturating or not */ + if ( (_magData.x >= 2040) | (_magData.x <= -2040) | + (_magData.y >= 2040) | (_magData.y <= -2040) | + (_magData.z >= 2040) | (_magData.z <= -2040) ) + { + /* Saturating .... increase the range if we can */ + switch(_magGain) + { + case LSM303_MAGGAIN_5_6: + setMagGain(LSM303_MAGGAIN_8_1); + readingValid = false; +#ifdef LSM303_DEBUG + Serial.println("Changing range to +/- 8.1"); +#endif + break; + case LSM303_MAGGAIN_4_7: + setMagGain(LSM303_MAGGAIN_5_6); + readingValid = false; +#ifdef LSM303_DEBUG + Serial.println("Changing range to +/- 5.6"); +#endif + break; + case LSM303_MAGGAIN_4_0: + setMagGain(LSM303_MAGGAIN_4_7); + readingValid = false; +#ifdef LSM303_DEBUG + Serial.println("Changing range to +/- 4.7"); +#endif + break; + case LSM303_MAGGAIN_2_5: + setMagGain(LSM303_MAGGAIN_4_0); + readingValid = false; +#ifdef LSM303_DEBUG + Serial.println("Changing range to +/- 4.0"); +#endif + break; + case LSM303_MAGGAIN_1_9: + setMagGain(LSM303_MAGGAIN_2_5); + readingValid = false; +#ifdef LSM303_DEBUG + Serial.println("Changing range to +/- 2.5"); +#endif + break; + case LSM303_MAGGAIN_1_3: + setMagGain(LSM303_MAGGAIN_1_9); + readingValid = false; +#ifdef LSM303_DEBUG + Serial.println("Changing range to +/- 1.9"); +#endif + break; + default: + readingValid = true; + break; + } + } + else + { + /* All values are withing range */ + readingValid = true; + } + } + } + + event->version = sizeof(sensors_event_t); + event->sensor_id = _sensorID; + event->type = SENSOR_TYPE_MAGNETIC_FIELD; + event->timestamp = timer.read_ms();//millis(); + event->magnetic.x = _magData.x / _lsm303Mag_Gauss_LSB_XY * SENSORS_GAUSS_TO_MICROTESLA; + event->magnetic.y = _magData.y / _lsm303Mag_Gauss_LSB_XY * SENSORS_GAUSS_TO_MICROTESLA; + event->magnetic.z = _magData.z / _lsm303Mag_Gauss_LSB_Z * SENSORS_GAUSS_TO_MICROTESLA; + + return true; +} + +/**************************************************************************/ +/*! + @brief Gets the sensor_t data +*/ +/**************************************************************************/ +void Adafruit_LSM303_Mag_Unified::getSensor(sensor_t *sensor) { + /* Clear the sensor_t object */ + memset(sensor, 0, sizeof(sensor_t)); + + /* Insert the sensor name in the fixed length char array */ + strncpy (sensor->name, "LSM303", sizeof(sensor->name) - 1); + sensor->name[sizeof(sensor->name)- 1] = 0; + sensor->version = 1; + sensor->sensor_id = _sensorID; + sensor->type = SENSOR_TYPE_MAGNETIC_FIELD; + sensor->min_delay = 0; + sensor->max_value = 0.0F; // TBD + sensor->min_value = 0.0F; // TBD + sensor->resolution = 0.0F; // TBD +}
diff -r eae1575da9ca -r 5d102be2566c Adafruit_10DOF/Adafruit_LSM303_U.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Adafruit_10DOF/Adafruit_LSM303_U.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,191 @@ +/*************************************************************************** + This is a library for the LSM303 Accelerometer and magnentometer/compass + + Designed specifically to work with the Adafruit LSM303DLHC Breakout + + These displays use I2C to communicate, 2 pins are required to interface. + + Adafruit invests time and resources providing this open source code, + please support Adafruit andopen-source hardware by purchasing products + from Adafruit! + + Written by Kevin Townsend for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ***************************************************************************/ +#ifndef __LSM303_H__ +#define __LSM303_H__ + +#include <Adafruit_Sensor.h> + + +/*========================================================================= + I2C ADDRESS/BITS + -----------------------------------------------------------------------*/ + #define LSM303_ADDRESS_ACCEL (0x32)// >> 1) // 0011001x + #define LSM303_ADDRESS_MAG (0x3C)// >> 1) // 0011110x + #define LSM303_WRITE (0x00) + #define LSM303_READ (0x01) +/*=========================================================================*/ + +/*========================================================================= + REGISTERS + -----------------------------------------------------------------------*/ + typedef enum + { // DEFAULT TYPE + LSM303_REGISTER_ACCEL_CTRL_REG1_A = 0x20, // 00000111 rw + LSM303_REGISTER_ACCEL_CTRL_REG2_A = 0x21, // 00000000 rw + LSM303_REGISTER_ACCEL_CTRL_REG3_A = 0x22, // 00000000 rw + LSM303_REGISTER_ACCEL_CTRL_REG4_A = 0x23, // 00000000 rw + LSM303_REGISTER_ACCEL_CTRL_REG5_A = 0x24, // 00000000 rw + LSM303_REGISTER_ACCEL_CTRL_REG6_A = 0x25, // 00000000 rw + LSM303_REGISTER_ACCEL_REFERENCE_A = 0x26, // 00000000 r + LSM303_REGISTER_ACCEL_STATUS_REG_A = 0x27, // 00000000 r + LSM303_REGISTER_ACCEL_OUT_X_L_A = 0x28, + LSM303_REGISTER_ACCEL_OUT_X_H_A = 0x29, + LSM303_REGISTER_ACCEL_OUT_Y_L_A = 0x2A, + LSM303_REGISTER_ACCEL_OUT_Y_H_A = 0x2B, + LSM303_REGISTER_ACCEL_OUT_Z_L_A = 0x2C, + LSM303_REGISTER_ACCEL_OUT_Z_H_A = 0x2D, + LSM303_REGISTER_ACCEL_FIFO_CTRL_REG_A = 0x2E, + LSM303_REGISTER_ACCEL_FIFO_SRC_REG_A = 0x2F, + LSM303_REGISTER_ACCEL_INT1_CFG_A = 0x30, + LSM303_REGISTER_ACCEL_INT1_SOURCE_A = 0x31, + LSM303_REGISTER_ACCEL_INT1_THS_A = 0x32, + LSM303_REGISTER_ACCEL_INT1_DURATION_A = 0x33, + LSM303_REGISTER_ACCEL_INT2_CFG_A = 0x34, + LSM303_REGISTER_ACCEL_INT2_SOURCE_A = 0x35, + LSM303_REGISTER_ACCEL_INT2_THS_A = 0x36, + LSM303_REGISTER_ACCEL_INT2_DURATION_A = 0x37, + LSM303_REGISTER_ACCEL_CLICK_CFG_A = 0x38, + LSM303_REGISTER_ACCEL_CLICK_SRC_A = 0x39, + LSM303_REGISTER_ACCEL_CLICK_THS_A = 0x3A, + LSM303_REGISTER_ACCEL_TIME_LIMIT_A = 0x3B, + LSM303_REGISTER_ACCEL_TIME_LATENCY_A = 0x3C, + LSM303_REGISTER_ACCEL_TIME_WINDOW_A = 0x3D + } lsm303AccelRegisters_t; + + typedef enum + { + LSM303_REGISTER_MAG_CRA_REG_M = 0x00, + LSM303_REGISTER_MAG_CRB_REG_M = 0x01, + LSM303_REGISTER_MAG_MR_REG_M = 0x02, + LSM303_REGISTER_MAG_OUT_X_H_M = 0x03, + LSM303_REGISTER_MAG_OUT_X_L_M = 0x04, + LSM303_REGISTER_MAG_OUT_Z_H_M = 0x05, + LSM303_REGISTER_MAG_OUT_Z_L_M = 0x06, + LSM303_REGISTER_MAG_OUT_Y_H_M = 0x07, + LSM303_REGISTER_MAG_OUT_Y_L_M = 0x08, + LSM303_REGISTER_MAG_SR_REG_Mg = 0x09, + LSM303_REGISTER_MAG_IRA_REG_M = 0x0A, + LSM303_REGISTER_MAG_IRB_REG_M = 0x0B, + LSM303_REGISTER_MAG_IRC_REG_M = 0x0C, + LSM303_REGISTER_MAG_TEMP_OUT_H_M = 0x31, + LSM303_REGISTER_MAG_TEMP_OUT_L_M = 0x32 + } lsm303MagRegisters_t; +/*=========================================================================*/ + +/*========================================================================= + MAGNETOMETER GAIN SETTINGS + -----------------------------------------------------------------------*/ + typedef enum + { + LSM303_MAGGAIN_1_3 = 0x20, // +/- 1.3 + LSM303_MAGGAIN_1_9 = 0x40, // +/- 1.9 + LSM303_MAGGAIN_2_5 = 0x60, // +/- 2.5 + LSM303_MAGGAIN_4_0 = 0x80, // +/- 4.0 + LSM303_MAGGAIN_4_7 = 0xA0, // +/- 4.7 + LSM303_MAGGAIN_5_6 = 0xC0, // +/- 5.6 + LSM303_MAGGAIN_8_1 = 0xE0 // +/- 8.1 + } lsm303MagGain; +/*=========================================================================*/ + +/*========================================================================= + MAGNETOMETER UPDATE RATE SETTINGS + -----------------------------------------------------------------------*/ + typedef enum + { + LSM303_MAGRATE_0_7 = 0x00, // 0.75 Hz + LSM303_MAGRATE_1_5 = 0x01, // 1.5 Hz + LSM303_MAGRATE_3_0 = 0x62, // 3.0 Hz + LSM303_MAGRATE_7_5 = 0x03, // 7.5 Hz + LSM303_MAGRATE_15 = 0x04, // 15 Hz + LSM303_MAGRATE_30 = 0x05, // 30 Hz + LSM303_MAGRATE_75 = 0x06, // 75 Hz + LSM303_MAGRATE_220 = 0x07 // 200 Hz + } lsm303MagRate; +/*=========================================================================*/ + +/*========================================================================= + INTERNAL MAGNETOMETER DATA TYPE + -----------------------------------------------------------------------*/ + typedef struct lsm303MagData_s + { + float x; + float y; + float z; + float orientation; + } lsm303MagData; +/*=========================================================================*/ + +/*========================================================================= + INTERNAL ACCELERATION DATA TYPE + -----------------------------------------------------------------------*/ + typedef struct lsm303AccelData_s + { + float x; + float y; + float z; + } lsm303AccelData; +/*=========================================================================*/ + +/*========================================================================= + CHIP ID + -----------------------------------------------------------------------*/ + #define LSM303_ID (0b11010100) +/*=========================================================================*/ + +/* Unified sensor driver for the accelerometer */ +class Adafruit_LSM303_Accel_Unified// : public Adafruit_Sensor +{ + public: + Adafruit_LSM303_Accel_Unified(int32_t sensorID = -1); + + bool begin(void); + bool getEvent(sensors_event_t*); + void getSensor(sensor_t*); + + private: + lsm303AccelData _accelData; // Last read accelerometer data will be available here + int32_t _sensorID; + + void write8(byte address, byte reg, byte value); + byte read8(byte address, byte reg); + void read(void); +}; + +/* Unified sensor driver for the magnetometer */ +class Adafruit_LSM303_Mag_Unified //: public Adafruit_Sensor +{ + public: + Adafruit_LSM303_Mag_Unified(int32_t sensorID = -1); + + bool begin(void); + void enableAutoRange(bool enable); + void setMagGain(lsm303MagGain gain); + void setMagRate(lsm303MagRate rate); + bool getEvent(sensors_event_t*); + void getSensor(sensor_t*); + + private: + lsm303MagGain _magGain; + lsm303MagData _magData; // Last read magnetometer data will be available here + int32_t _sensorID; + bool _autoRangeEnabled; + + void write8(byte address, byte reg, byte value); + byte read8(byte address, byte reg); + void read(void); +}; + +#endif +
diff -r eae1575da9ca -r 5d102be2566c Adafruit_10DOF/Adafruit_Sensor.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Adafruit_10DOF/Adafruit_Sensor.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,170 @@ +/* +* Copyright (C) 2008 The Android Open Source Project +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software< /span> +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*/ + +/* Update by K. Townsend (Adafruit Industries) for lighter typedefs, and + * extended sensor support to include color, voltage and current */ + +#ifndef _ADAFRUIT_SENSOR_H +#define _ADAFRUIT_SENSOR_H +#include <stdint.h> +#include "mbed.h" + +#include "Timer.h" + + +/* Intentionally modeled after sensors.h in the Android API: + * https://github.com/android/platform_hardware_libhardware/blob/master/include/hardware/sensors.h */ + +/* Constants */ +#define SENSORS_GRAVITY_EARTH (9.80665F) /**< Earth's gravity in m/s^2 */ +#define SENSORS_GRAVITY_MOON (1.6F) /**< The moon's gravity in m/s^2 */ +#define SENSORS_GRAVITY_SUN (275.0F) /**< The sun's gravity in m/s^2 */ +#define SENSORS_GRAVITY_STANDARD (SENSORS_GRAVITY_EARTH) +#define SENSORS_MAGFIELD_EARTH_MAX (60.0F) /**< Maximum magnetic field on Earth's surface */ +#define SENSORS_MAGFIELD_EARTH_MIN (30.0F) /**< Minimum magnetic field on Earth's surface */ +#define SENSORS_PRESSURE_SEALEVELHPA (1013.25F) /**< Average sea level pressure is 1013.25 hPa */ +#define SENSORS_DPS_TO_RADS (0.017453293F) /**< Degrees/s to rad/s multiplier */ +#define SENSORS_GAUSS_TO_MICROTESLA (100) /**< Gauss to micro-Tesla multiplier */ + +extern mbed::I2C* i2c; +extern Timer timer; + +typedef uint8_t byte; + +/** Sensor types */ +typedef enum +{ + SENSOR_TYPE_ACCELEROMETER = (1), /**< Gravity + linear acceleration */ + SENSOR_TYPE_MAGNETIC_FIELD = (2), + SENSOR_TYPE_ORIENTATION = (3), + SENSOR_TYPE_GYROSCOPE = (4), + SENSOR_TYPE_LIGHT = (5), + SENSOR_TYPE_PRESSURE = (6), + SENSOR_TYPE_PROXIMITY = (8), + SENSOR_TYPE_GRAVITY = (9), + SENSOR_TYPE_LINEAR_ACCELERATION = (10), /**< Acceleration not including gravity */ + SENSOR_TYPE_ROTATION_VECTOR = (11), + SENSOR_TYPE_RELATIVE_HUMIDITY = (12), + SENSOR_TYPE_AMBIENT_TEMPERATURE = (13), + SENSOR_TYPE_VOLTAGE = (15), + SENSOR_TYPE_CURRENT = (16), + SENSOR_TYPE_COLOR = (17) +} sensors_type_t; + +/** struct sensors_vec_s is used to return a vector in a common format. */ +typedef struct { + union { + float v[3]; + struct { + float x; + float y; + float z; + }; + /* Orientation sensors */ + struct { + float roll; /**< Rotation around the longitudinal axis (the plane body, 'X axis'). Roll is positive and increasing when moving downward. -90�<=roll<=90� */ + float pitch; /**< Rotation around the lateral axis (the wing span, 'Y axis'). Pitch is positive and increasing when moving upwards. -180�<=pitch<=180�) */ + float heading; /**< Angle between the longitudinal axis (the plane body) and magnetic north, measured clockwise when viewing from the top of the device. 0-359� */ + }; + }; + int8_t status; + uint8_t reserved[3]; +} sensors_vec_t; + +/** struct sensors_color_s is used to return color data in a common format. */ +typedef struct { + union { + float c[3]; + /* RGB color space */ + struct { + float r; /**< Red component */ + float g; /**< Green component */ + float b; /**< Blue component */ + }; + }; + uint32_t rgba; /**< 24-bit RGBA value */ +} sensors_color_t; + +/* Sensor event (36 bytes) */ +/** struct sensor_event_s is used to provide a single sensor event in a common format. */ +typedef struct +{ + int32_t version; /**< must be sizeof(struct sensors_event_t) */ + int32_t sensor_id; /**< unique sensor identifier */ + int32_t type; /**< sensor type */ + int32_t reserved0; /**< reserved */ + int32_t timestamp; /**< time is in milliseconds */ + union + { + float data[4]; + sensors_vec_t acceleration; /**< acceleration values are in meter per second per second (m/s^2) */ + sensors_vec_t magnetic; /**< magnetic vector values are in micro-Tesla (uT) */ + sensors_vec_t orientation; /**< orientation values are in degrees */ + sensors_vec_t gyro; /**< gyroscope values are in rad/s */ + float temperature; /**< temperature is in degrees centigrade (Celsius) */ + float distance; /**< distance in centimeters */ + float light; /**< light in SI lux units */ + float pressure; /**< pressure in hectopascal (hPa) */ + float relative_humidity; /**< relative humidity in percent */ + float current; /**< current in milliamps (mA) */ + float voltage; /**< voltage in volts (V) */ + sensors_color_t color; /**< color in RGB component values */ + }; +} sensors_event_t; + +/* Sensor details (40 bytes) */ +/** struct sensor_s is used to describe basic information about a specific sensor. */ +typedef struct +{ + char name[12]; /**< sensor name */ + int32_t version; /**< version of the hardware + driver */ + int32_t sensor_id; /**< unique sensor identifier */ + int32_t type; /**< this sensor's type (ex. SENSOR_TYPE_LIGHT) */ + float max_value; /**< maximum value of this sensor's value in SI units */ + float min_value; /**< minimum value of this sensor's value in SI units */ + float resolution; /**< smallest difference between two values reported by this sensor */ + int32_t min_delay; /**< min delay in microseconds between events. zero = not a constant rate */ +} sensor_t; + +//class Adafruit_Sensor { +// public: +// // Constructor(s) +// void constructor(); +// +// // These must be defined by the subclass +// virtual void enableAutoRange(bool enabled) {}; +// virtual void getEvent(sensors_event_t*); +// virtual void getSensor(sensor_t*); +// +// private: +// bool _autoRange; +//}; +class Adafruit_Sensor { + public: + // Constructor(s) + Adafruit_Sensor() {} + virtual ~Adafruit_Sensor() {} + + // These must be defined by the subclass + virtual void enableAutoRange(bool enabled) {}; + virtual bool getEvent(sensors_event_t*) = 0; + virtual void getSensor(sensor_t*) = 0; + + private: + bool _autoRange; +}; +#endif +
diff -r eae1575da9ca -r 5d102be2566c EthernetInterface.lib --- a/EthernetInterface.lib Fri Mar 08 02:24:33 2013 +0000 +++ b/EthernetInterface.lib Wed Oct 07 20:42:51 2015 +0000 @@ -1,1 +1,1 @@ -http://mbed.org/users/mbed_official/code/EthernetInterface/#9b2d10dc0392 +http://mbed.org/users/mbed_official/code/EthernetInterface/#2fc406e2553f
diff -r eae1575da9ca -r 5d102be2566c HTTP-Server.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/HTTP-Server.lib Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,1 @@ +https://developer.mbed.org/users/webOnBoard/code/HTTP-Server/#d03f12a19999
diff -r eae1575da9ca -r 5d102be2566c Webpage.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Webpage.lib Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,1 @@ +https://developer.mbed.org/users/webOnBoard/code/Webpage/#256cd901cbb1
diff -r eae1575da9ca -r 5d102be2566c main.cpp --- a/main.cpp Fri Mar 08 02:24:33 2013 +0000 +++ b/main.cpp Wed Oct 07 20:42:51 2015 +0000 @@ -1,96 +1,203 @@ #include "mbed.h" #include "EthernetInterface.h" +#include "HTTPServer.h" #include <stdio.h> #include <string.h> +//#include "webpage.h" + + +#include "Adafruit_Sensor.h" +#include "Adafruit_LSM303_U.h" +#include "Adafruit_BMP085_U.h" +#include "Adafruit_L3GD20_U.h" +#include "Adafruit_10DOF.h" + #define PORT 80 +#include <string> + + +/* Assign a unique ID to the sensors */ +Adafruit_10DOF dof = Adafruit_10DOF(); +Adafruit_LSM303_Accel_Unified accel = Adafruit_LSM303_Accel_Unified(30301L); +Adafruit_LSM303_Mag_Unified mag = Adafruit_LSM303_Mag_Unified(30302L); +Adafruit_BMP085_Unified bmp = Adafruit_BMP085_Unified(18001L); +Adafruit_L3GD20_Unified gyro = Adafruit_L3GD20_Unified(20L); + + +// Update this with the correct SLP for accurate altitude measurements +float seaLevelPressure = SENSORS_PRESSURE_SEALEVELHPA; + +mbed::I2C* i2c; +Timer timer; EthernetInterface eth; TCPSocketServer svr; -bool serverIsListened = false; +bool serverIsListening = false; TCPSocketConnection client; bool clientIsConnected = false; DigitalOut led1(LED1); //server listning status DigitalOut led2(LED2); //socket connecting status +DigitalOut led3(LED3); //last color Ticker ledTick; +HTTPServer create_simple_server() +{ + HTTPServer srv; + srv.add_request_handler("DELETE", new DeleteRequestHandler()); + srv.add_request_handler("GET", new GetRequestHandler()); + srv.add_request_handler("PUT", new PutRequestHandler()); + return srv; +} +HTTPServer create_interactive_server() +{ + HTTPServer srv(new InteractiveHTMLFormatter()); + srv.add_request_handler("GET", new ComplexRequestHandler()); + return srv; +} +HTTPServer create_simple_interactive_server() +{ + HTTPServer srv(new InteractiveHTMLFormatter()); + srv.add_request_handler("GET", new GetRequestHandler()); + return srv; +} void ledTickfunc() { - if(serverIsListened) { + if(serverIsListening) { led1 = !led1; } else { led1 = false; } } +void setup(void) +{ + + printf("Adafruit 10DOF Tester \r\n"); + + /* Initialise the sensors */ + if(!accel.begin()) + { + /* There was a problem detecting the ADXL345 ... check your connections */ + printf("Ooops, no LSM303 detected ... Check your wiring!\r\n"); + //while(1); + } + printf("Adafruit 10DOF Accel setup complete \r\n"); + if(!mag.begin()) + { + /* There was a problem detecting the LSM303 ... check your connections */ + printf("Ooops, no LSM303 detected ... Check your wiring!\r\n"); + //while(1); + } + printf("Adafruit 10DOF Mag setup complete \r\n"); + if(!gyro.begin()) + { + /* There was a problem detecting the L3GD20 ... check your connections */ + printf("Ooops, no L3GD20 detected ... Check your wiring or I2C ADDR!\r\n"); + //while(1); + } + printf("Adafruit 10DOF Gyro setup complete \r\n"); + + /* Display some basic information on this sensor */ + //displaySensorDetails(); +} + +/**************************************************************************/ +/*! + @brief Constantly check the roll/pitch/heading/altitude/temperature +*/ +/**************************************************************************/ +void loop(void) +{ + sensors_event_t accel_event; + sensors_event_t mag_event; + sensors_vec_t orientation; + + + /* Calculate pitch and roll from the raw accelerometer data */ + accel.getEvent(&accel_event); + if (dof.accelGetOrientation(&accel_event, &orientation)) + { + /* 'orientation' should have valid .roll and .pitch fields */ + printf("Roll: %f \n\r",orientation.roll); + printf("Pitch: %f \n\r",orientation.pitch); + } + + /* Calculate the heading using the magnetometer */ + mag.getEvent(&mag_event); + if (dof.magGetOrientation(SENSOR_AXIS_Z, &mag_event, &orientation)) + { + /* 'orientation' should have valid .heading data now */ + printf("Heading: %f\n\r", orientation.heading); + } + + printf("\n\r"); +} + +void getOrientation(char * xmlHeader){ + sensors_event_t accel_event; + sensors_event_t mag_event; + sensors_event_t bmp_event; + sensors_vec_t orientation; + //float horizontal; + //float vertical; + uint32_t altitude = 1000;//rand() % 300 +1; + uint32_t horizontal = 30;//rand() % 300 +1; + uint32_t vertical = 45;//rand() % 300 +1; + uint32_t heading = 33;//rand() % 300 +1; + uint32_t switch1 = 0;//rand() % 1; + uint32_t switch2 = 1;//rand() % 1; + //char echoHeader[256] = {}; + + //accel.getEvent(&accel_event); + //if (dof.accelGetOrientation(&accel_event, &orientation)){ + // horizontal = (uint32_t) orientation.roll; + // vertical = (uint32_t) orientation.pitch; + //} + sprintf(xmlHeader, "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n\r"); + sprintf(xmlHeader, "<AHRS>\n\r"); + sprintf(xmlHeader, " <DATA>\n\r"); + sprintf(xmlHeader, " <HORIZONTAL>%d</HORIZONTAL>\n\r",horizontal); + sprintf(xmlHeader, " <VERTICAL>%d</VERTICAL>\n\r",vertical); + sprintf(xmlHeader, " <HEADING>%d</HEADING>\n\r",heading); + sprintf(xmlHeader, " <SWITCH1>%d</SWITCH1>\n\r",switch1); + sprintf(xmlHeader, " <SWITCH2>%d</SWITCH2>\n\r",switch2); + sprintf(xmlHeader, " <COLOR>purple</COLOR>\n\r"); + sprintf(xmlHeader, " </DATA>\n\r"); + sprintf(xmlHeader, "</AHRS>\n\r"); + sprintf(xmlHeader, "\n\r"); + //return echoHeader; + +} + int main (void) { ledTick.attach(&ledTickfunc,0.5); + i2c = new mbed::I2C(I2C_SDA, I2C_SCL); + + setup(); + loop(); + + EthernetInterface eth; //setup ethernet interface eth.init(); //Use DHCP eth.connect(); + printf("IP Address is %s\n\r", eth.getIPAddress()); - //setup tcp socket - if(svr.bind(PORT)< 0) { - printf("tcp server bind failed.\n\r"); + HTTPServer srv = create_simple_interactive_server();//create_interactive_server();//create_simple_server(); + + if(!srv.init(PORT)) + { + printf("Error while initializing the server\n"); + eth.disconnect(); return -1; - } else { - printf("tcp server bind successed.\n\r"); - serverIsListened = true; - } - - if(svr.listen(1) < 0) { - printf("tcp server listen failed.\n\r"); - return -1; - } else { - printf("tcp server is listening...\n\r"); } - - //listening for http GET request - while (serverIsListened) { - //blocking mode(never timeout) - if(svr.accept(client)<0) { - printf("failed to accept connection.\n\r"); - } else { - printf("connection success!\n\rIP: %s\n\r",client.get_address()); - clientIsConnected = true; - led2 = true; - - while(clientIsConnected) { - char buffer[1024] = {}; - switch(client.receive(buffer, 1023)) { - case 0: - printf("recieved buffer is empty.\n\r"); - clientIsConnected = false; - break; - case -1: - printf("failed to read data from client.\n\r"); - clientIsConnected = false; - break; - default: - printf("Recieved Data: %d\n\r\n\r%.*s\n\r",strlen(buffer),strlen(buffer),buffer); - if(buffer[0] == 'G' && buffer[1] == 'E' && buffer[2] == 'T' ) { - printf("GET request incomming.\n\r"); - //setup http response header & data - char echoHeader[256] = {}; - sprintf(echoHeader,"HTTP/1.1 200 OK\n\rContent-Length: %d\n\rContent-Type: text\n\rConnection: Close\n\r\n\r",strlen(buffer)); - client.send(echoHeader,strlen(echoHeader)); - client.send(buffer,strlen(buffer)); - clientIsConnected = false; - printf("echo back done.\n\r"); - } - break; - } - } - printf("close connection.\n\rtcp server is listening...\n\r"); - client.close(); - led2 = false; - } - } + srv.run(); + }
diff -r eae1575da9ca -r 5d102be2566c mbed-rpc.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rpc.lib Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,1 @@ +https://developer.mbed.org/users/webOnBoard/code/mbed-rpc/#a1a58dcfece8
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos.lib --- a/mbed-rtos.lib Fri Mar 08 02:24:33 2013 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,1 +0,0 @@ -http://mbed.org/users/mbed_official/code/mbed-rtos/#53e6cccd8782
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/Mail.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/Mail.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,109 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#ifndef MAIL_H +#define MAIL_H + +#include <stdint.h> +#include <string.h> + +#include "cmsis_os.h" + +namespace rtos { + +/** The Mail class allow to control, send, receive, or wait for mail. + A mail is a memory block that is send to a thread or interrupt service routine. + @tparam T data type of a single message element. + @tparam queue_sz maximum number of messages in queue. +*/ +template<typename T, uint32_t queue_sz> +class Mail { +public: + /** Create and Initialise Mail queue. */ + Mail() { + #ifdef CMSIS_OS_RTX + memset(_mail_q, 0, sizeof(_mail_q)); + _mail_p[0] = _mail_q; + + memset(_mail_m, 0, sizeof(_mail_m)); + _mail_p[1] = _mail_m; + + _mail_def.pool = _mail_p; + _mail_def.queue_sz = queue_sz; + _mail_def.item_sz = sizeof(T); + #endif + _mail_id = osMailCreate(&_mail_def, NULL); + } + + /** Allocate a memory block of type T + @param millisec timeout value or 0 in case of no time-out. (default: 0). + @return pointer to memory block that can be filled with mail or NULL in case error. + */ + T* alloc(uint32_t millisec=0) { + return (T*)osMailAlloc(_mail_id, millisec); + } + + /** Allocate a memory block of type T and set memory block to zero. + @param millisec timeout value or 0 in case of no time-out. (default: 0). + @return pointer to memory block that can be filled with mail or NULL in case error. + */ + T* calloc(uint32_t millisec=0) { + return (T*)osMailCAlloc(_mail_id, millisec); + } + + /** Put a mail in the queue. + @param mptr memory block previously allocated with Mail::alloc or Mail::calloc. + @return status code that indicates the execution status of the function. + */ + osStatus put(T *mptr) { + return osMailPut(_mail_id, (void*)mptr); + } + + /** Get a mail from a queue. + @param millisec timeout value or 0 in case of no time-out. (default: osWaitForever). + @return event that contains mail information or error code. + */ + osEvent get(uint32_t millisec=osWaitForever) { + return osMailGet(_mail_id, millisec); + } + + /** Free a memory block from a mail. + @param mptr pointer to the memory block that was obtained with Mail::get. + @return status code that indicates the execution status of the function. + */ + osStatus free(T *mptr) { + return osMailFree(_mail_id, (void*)mptr); + } + +private: + osMailQId _mail_id; + osMailQDef_t _mail_def; +#ifdef CMSIS_OS_RTX + uint32_t _mail_q[4+(queue_sz)]; + uint32_t _mail_m[3+((sizeof(T)+3)/4)*(queue_sz)]; + void *_mail_p[2]; +#endif +}; + +} + +#endif +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/MemoryPool.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/MemoryPool.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,82 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#ifndef MEMORYPOOL_H +#define MEMORYPOOL_H + +#include <stdint.h> +#include <string.h> + +#include "cmsis_os.h" + +namespace rtos { + +/** Define and manage fixed-size memory pools of objects of a given type. + @tparam T data type of a single object (element). + @tparam queue_sz maximum number of objects (elements) in the memory pool. +*/ +template<typename T, uint32_t pool_sz> +class MemoryPool { +public: + /** Create and Initialize a memory pool. */ + MemoryPool() { + #ifdef CMSIS_OS_RTX + memset(_pool_m, 0, sizeof(_pool_m)); + _pool_def.pool = _pool_m; + + _pool_def.pool_sz = pool_sz; + _pool_def.item_sz = sizeof(T); + #endif + _pool_id = osPoolCreate(&_pool_def); + } + + /** Allocate a memory block of type T from a memory pool. + @return address of the allocated memory block or NULL in case of no memory available. + */ + T* alloc(void) { + return (T*)osPoolAlloc(_pool_id); + } + + /** Allocate a memory block of type T from a memory pool and set memory block to zero. + @return address of the allocated memory block or NULL in case of no memory available. + */ + T* calloc(void) { + return (T*)osPoolCAlloc(_pool_id); + } + + /** Return an allocated memory block back to a specific memory pool. + @param address of the allocated memory block that is returned to the memory pool. + @return status code that indicates the execution status of the function. + */ + osStatus free(T *block) { + return osPoolFree(_pool_id, (void*)block); + } + +private: + osPoolId _pool_id; + osPoolDef_t _pool_def; +#ifdef CMSIS_OS_RTX + uint32_t _pool_m[3+((sizeof(T)+3)/4)*(pool_sz)]; +#endif +}; + +} +#endif
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/Mutex.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/Mutex.cpp Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,56 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#include "Mutex.h" + +#include <string.h> +#include "mbed_error.h" + +namespace rtos { + +Mutex::Mutex() { +#ifdef CMSIS_OS_RTX + memset(_mutex_data, 0, sizeof(_mutex_data)); + _osMutexDef.mutex = _mutex_data; +#endif + _osMutexId = osMutexCreate(&_osMutexDef); + if (_osMutexId == NULL) { + error("Error initializing the mutex object\n"); + } +} + +osStatus Mutex::lock(uint32_t millisec) { + return osMutexWait(_osMutexId, millisec); +} + +bool Mutex::trylock() { + return (osMutexWait(_osMutexId, 0) == osOK); +} + +osStatus Mutex::unlock() { + return osMutexRelease(_osMutexId); +} + +Mutex::~Mutex() { + osMutexDelete(_osMutexId); +} + +}
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/Mutex.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/Mutex.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,65 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#ifndef MUTEX_H +#define MUTEX_H + +#include <stdint.h> +#include "cmsis_os.h" + +namespace rtos { + +/** The Mutex class is used to synchronise the execution of threads. + This is for example used to protect access to a shared resource. +*/ +class Mutex { +public: + /** Create and Initialize a Mutex object */ + Mutex(); + + /** Wait until a Mutex becomes available. + @param millisec timeout value or 0 in case of no time-out. (default: osWaitForever) + @return status code that indicates the execution status of the function. + */ + osStatus lock(uint32_t millisec=osWaitForever); + + /** Try to lock the mutex, and return immediately + @return true if the mutex was acquired, false otherwise. + */ + bool trylock(); + + /** Unlock the mutex that has previously been locked by the same thread + @return status code that indicates the execution status of the function. + */ + osStatus unlock(); + + ~Mutex(); + +private: + osMutexId _osMutexId; + osMutexDef_t _osMutexDef; +#ifdef CMSIS_OS_RTX + int32_t _mutex_data[3]; +#endif +}; + +} +#endif
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/Queue.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/Queue.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,81 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#ifndef QUEUE_H +#define QUEUE_H + +#include <stdint.h> +#include <string.h> + +#include "cmsis_os.h" +#include "mbed_error.h" + +namespace rtos { + +/** The Queue class allow to control, send, receive, or wait for messages. + A message can be a integer or pointer value to a certain type T that is send + to a thread or interrupt service routine. + @tparam T data type of a single message element. + @tparam queue_sz maximum number of messages in queue. +*/ +template<typename T, uint32_t queue_sz> +class Queue { +public: + /** Create and initialise a message Queue. */ + Queue() { + #ifdef CMSIS_OS_RTX + memset(_queue_q, 0, sizeof(_queue_q)); + _queue_def.pool = _queue_q; + _queue_def.queue_sz = queue_sz; + #endif + _queue_id = osMessageCreate(&_queue_def, NULL); + if (_queue_id == NULL) { + error("Error initialising the queue object\n"); + } + } + + /** Put a message in a Queue. + @param data message pointer. + @param millisec timeout value or 0 in case of no time-out. (default: 0) + @return status code that indicates the execution status of the function. + */ + osStatus put(T* data, uint32_t millisec=0) { + return osMessagePut(_queue_id, (uint32_t)data, millisec); + } + + /** Get a message or Wait for a message from a Queue. + @param millisec timeout value or 0 in case of no time-out. (default: osWaitForever). + @return event information that includes the message and the status code. + */ + osEvent get(uint32_t millisec=osWaitForever) { + return osMessageGet(_queue_id, millisec); + } + +private: + osMessageQId _queue_id; + osMessageQDef_t _queue_def; +#ifdef CMSIS_OS_RTX + uint32_t _queue_q[4+(queue_sz)]; +#endif +}; + +} +#endif
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/RtosTimer.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/RtosTimer.cpp Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,53 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#include "RtosTimer.h" + +#include <string.h> + +#include "cmsis_os.h" +#include "mbed_error.h" + +namespace rtos { + +RtosTimer::RtosTimer(void (*periodic_task)(void const *argument), os_timer_type type, void *argument) { +#ifdef CMSIS_OS_RTX + _timer.ptimer = periodic_task; + + memset(_timer_data, 0, sizeof(_timer_data)); + _timer.timer = _timer_data; +#endif + _timer_id = osTimerCreate(&_timer, type, argument); +} + +osStatus RtosTimer::start(uint32_t millisec) { + return osTimerStart(_timer_id, millisec); +} + +osStatus RtosTimer::stop(void) { + return osTimerStop(_timer_id); +} + +RtosTimer::~RtosTimer() { + osTimerDelete(_timer_id); +} + +}
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/RtosTimer.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/RtosTimer.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,71 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#ifndef RTOS_TIMER_H +#define RTOS_TIMER_H + +#include <stdint.h> +#include "cmsis_os.h" + +namespace rtos { + +/** The RtosTimer class allow creating and and controlling of timer functions in the system. + A timer function is called when a time period expires whereby both on-shot and + periodic timers are possible. A timer can be started, restarted, or stopped. + + Timers are handled in the thread osTimerThread. + Callback functions run under control of this thread and may use CMSIS-RTOS API calls. +*/ +class RtosTimer { +public: + /** Create and Start timer. + @param task name of the timer call back function. + @param type osTimerOnce for one-shot or osTimerPeriodic for periodic behaviour. (default: osTimerPeriodic) + @param argument argument to the timer call back function. (default: NULL) + */ + RtosTimer(void (*task)(void const *argument), + os_timer_type type=osTimerPeriodic, + void *argument=NULL); + + /** Stop the timer. + @return status code that indicates the execution status of the function. + */ + osStatus stop(void); + + /** start a timer. + @param millisec time delay value of the timer. + @return status code that indicates the execution status of the function. + */ + osStatus start(uint32_t millisec); + + ~RtosTimer(); + +private: + osTimerId _timer_id; + osTimerDef_t _timer; +#ifdef CMSIS_OS_RTX + uint32_t _timer_data[5]; +#endif +}; + +} + +#endif
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/Semaphore.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/Semaphore.cpp Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,48 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#include "Semaphore.h" + +#include <string.h> + +namespace rtos { + +Semaphore::Semaphore(int32_t count) { +#ifdef CMSIS_OS_RTX + memset(_semaphore_data, 0, sizeof(_semaphore_data)); + _osSemaphoreDef.semaphore = _semaphore_data; +#endif + _osSemaphoreId = osSemaphoreCreate(&_osSemaphoreDef, count); +} + +int32_t Semaphore::wait(uint32_t millisec) { + return osSemaphoreWait(_osSemaphoreId, millisec); +} + +osStatus Semaphore::release(void) { + return osSemaphoreRelease(_osSemaphoreId); +} + +Semaphore::~Semaphore() { + osSemaphoreDelete(_osSemaphoreId); +} + +}
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/Semaphore.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/Semaphore.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,60 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#ifndef SEMAPHORE_H +#define SEMAPHORE_H + +#include <stdint.h> +#include "cmsis_os.h" + +namespace rtos { + +/** The Semaphore class is used to manage and protect access to a set of shared resources. */ +class Semaphore { +public: + /** Create and Initialize a Semaphore object used for managing resources. + @param number of available resources; maximum index value is (count-1). + */ + Semaphore(int32_t count); + + /** Wait until a Semaphore resource becomes available. + @param millisec timeout value or 0 in case of no time-out. (default: osWaitForever). + @return number of available tokens, or -1 in case of incorrect parameters + */ + int32_t wait(uint32_t millisec=osWaitForever); + + /** Release a Semaphore resource that was obtain with Semaphore::wait. + @return status code that indicates the execution status of the function. + */ + osStatus release(void); + + ~Semaphore(); + +private: + osSemaphoreId _osSemaphoreId; + osSemaphoreDef_t _osSemaphoreDef; +#ifdef CMSIS_OS_RTX + uint32_t _semaphore_data[2]; +#endif +}; + +} +#endif
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/Thread.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/Thread.cpp Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,100 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#include "Thread.h" + +#include "mbed_error.h" + +namespace rtos { + +Thread::Thread(void (*task)(void const *argument), void *argument, + osPriority priority, uint32_t stack_size, unsigned char *stack_pointer) { +#ifdef CMSIS_OS_RTX + _thread_def.pthread = task; + _thread_def.tpriority = priority; + _thread_def.stacksize = stack_size; +#ifndef __MBED_CMSIS_RTOS_CA9 + if (stack_pointer != NULL) { + _thread_def.stack_pointer = (uint32_t*)stack_pointer; + _dynamic_stack = false; + } else { + _thread_def.stack_pointer = new uint32_t[stack_size/sizeof(uint32_t)]; + if (_thread_def.stack_pointer == NULL) + error("Error allocating the stack memory\n"); + _dynamic_stack = true; + } +#endif +#endif + _tid = osThreadCreate(&_thread_def, argument); +} + +osStatus Thread::terminate() { + return osThreadTerminate(_tid); +} + +osStatus Thread::set_priority(osPriority priority) { + return osThreadSetPriority(_tid, priority); +} + +osPriority Thread::get_priority() { + return osThreadGetPriority(_tid); +} + +int32_t Thread::signal_set(int32_t signals) { + return osSignalSet(_tid, signals); +} + +Thread::State Thread::get_state() { +#ifndef __MBED_CMSIS_RTOS_CA9 + return ((State)_thread_def.tcb.state); +#else + uint8_t status; + status = osThreadGetState(_tid); + return ((State)status); +#endif +} + +osEvent Thread::signal_wait(int32_t signals, uint32_t millisec) { + return osSignalWait(signals, millisec); +} + +osStatus Thread::wait(uint32_t millisec) { + return osDelay(millisec); +} + +osStatus Thread::yield() { + return osThreadYield(); +} + +osThreadId Thread::gettid() { + return osThreadGetId(); +} + +Thread::~Thread() { + terminate(); +#ifndef __MBED_CMSIS_RTOS_CA9 + if (_dynamic_stack) { + delete[] (_thread_def.stack_pointer); + } +#endif +} + +}
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/Thread.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/Thread.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,118 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#ifndef THREAD_H +#define THREAD_H + +#include <stdint.h> +#include "cmsis_os.h" + +namespace rtos { + +/** The Thread class allow defining, creating, and controlling thread functions in the system. */ +class Thread { +public: + /** Create a new thread, and start it executing the specified function. + @param task function to be executed by this thread. + @param argument pointer that is passed to the thread function as start argument. (default: NULL). + @param priority initial priority of the thread function. (default: osPriorityNormal). + @param stack_size stack size (in bytes) requirements for the thread function. (default: DEFAULT_STACK_SIZE). + @param stack_pointer pointer to the stack area to be used by this thread (default: NULL). + */ + Thread(void (*task)(void const *argument), void *argument=NULL, + osPriority priority=osPriorityNormal, + uint32_t stack_size=DEFAULT_STACK_SIZE, + unsigned char *stack_pointer=NULL); + + /** Terminate execution of a thread and remove it from Active Threads + @return status code that indicates the execution status of the function. + */ + osStatus terminate(); + + /** Set priority of an active thread + @param priority new priority value for the thread function. + @return status code that indicates the execution status of the function. + */ + osStatus set_priority(osPriority priority); + + /** Get priority of an active thread + @return current priority value of the thread function. + */ + osPriority get_priority(); + + /** Set the specified Signal Flags of an active thread. + @param signals specifies the signal flags of the thread that should be set. + @return previous signal flags of the specified thread or 0x80000000 in case of incorrect parameters. + */ + int32_t signal_set(int32_t signals); + + /** State of the Thread */ + enum State { + Inactive, /**< Not created or terminated */ + Ready, /**< Ready to run */ + Running, /**< Running */ + WaitingDelay, /**< Waiting for a delay to occur */ + WaitingInterval, /**< Waiting for an interval to occur */ + WaitingOr, /**< Waiting for one event in a set to occur */ + WaitingAnd, /**< Waiting for multiple events in a set to occur */ + WaitingSemaphore, /**< Waiting for a semaphore event to occur */ + WaitingMailbox, /**< Waiting for a mailbox event to occur */ + WaitingMutex, /**< Waiting for a mutex event to occur */ + }; + + /** State of this Thread + @return the State of this Thread + */ + State get_state(); + + /** Wait for one or more Signal Flags to become signaled for the current RUNNING thread. + @param signals wait until all specified signal flags set or 0 for any single signal flag. + @param millisec timeout value or 0 in case of no time-out. (default: osWaitForever). + @return event flag information or error code. + */ + static osEvent signal_wait(int32_t signals, uint32_t millisec=osWaitForever); + + /** Wait for a specified time period in millisec: + @param millisec time delay value + @return status code that indicates the execution status of the function. + */ + static osStatus wait(uint32_t millisec); + + /** Pass control to next thread that is in state READY. + @return status code that indicates the execution status of the function. + */ + static osStatus yield(); + + /** Get the thread id of the current running thread. + @return thread ID for reference by other functions or NULL in case of error. + */ + static osThreadId gettid(); + + virtual ~Thread(); + +private: + osThreadId _tid; + osThreadDef_t _thread_def; + bool _dynamic_stack; +}; + +} +#endif
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtos/rtos.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtos/rtos.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,35 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2012 ARM Limited + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ +#ifndef RTOS_H +#define RTOS_H + +#include "Thread.h" +#include "Mutex.h" +#include "RtosTimer.h" +#include "Semaphore.h" +#include "Mail.h" +#include "MemoryPool.h" +#include "Queue.h" + +using namespace rtos; + +#endif
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/HAL_CA.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/HAL_CA.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,126 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: HAL_CA.C + * Purpose: Hardware Abstraction Layer for Cortex-A + * Rev.: + *---------------------------------------------------------------------------- + * + * Copyright (c) 2012 ARM Limited + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_HAL_CA.h" + +/*--------------------------- os_init_context -------------------------------*/ + +void rt_init_stack (P_TCB p_TCB, FUNCP task_body) { + /* Prepare TCB and saved context for a first time start of a task. */ + U32 *stk,i,size; + + /* Prepare a complete interrupt frame for first task start */ + size = p_TCB->priv_stack >> 2; + if (size == 0) { + size = (U16)os_stackinfo >> 2; + } + /* Write to the top of stack. */ + stk = &p_TCB->stack[size]; + + /* Auto correct to 8-byte ARM stack alignment. */ + if ((U32)stk & 0x04) { + stk--; + } + + stk -= 16; + + /* Initial PC and default CPSR */ + stk[14] = (U32)task_body; + /* Task run mode is inherited from the startup file. */ + /* (non-privileged USER or privileged SYSTEM mode) */ + stk[15] = (os_flags & 1) ? INIT_CPSR_SYS : INIT_CPSR_USER; + /* Set T-bit if task function in Thumb mode. */ + if ((U32)task_body & 1) { + stk[15] |= CPSR_T_BIT; + } + /* Assign a void pointer to R0. */ + stk[8] = (U32)p_TCB->msg; + /* Clear R1-R12,LR registers. */ + for (i = 0; i < 8; i++) { + stk[i] = 0; + } + for (i = 9; i < 14; i++) { + stk[i] = 0; + } + + /* Initial Task stack pointer. */ + p_TCB->tsk_stack = (U32)stk; + + /* Task entry point. */ + p_TCB->ptask = task_body; + + /* Set a magic word for checking of stack overflow. */ + p_TCB->stack[0] = MAGIC_WORD; +} + + +/*--------------------------- rt_ret_val ----------------------------------*/ + +static __inline U32 *rt_ret_regs (P_TCB p_TCB) { + /* Get pointer to task return value registers (R0..R3) in Stack */ +#if (__TARGET_FPU_VFP) + if (p_TCB->stack_frame & 0x2) { + /* Extended Stack Frame: S0-31,FPSCR,Reserved,R4-R11,R0-R3,R12,LR,PC,xPSR */ + return (U32 *)(p_TCB->tsk_stack + 8*4 + 34*4); + } else { + /* Basic Stack Frame: R4-R11,R0-R3,R12,LR,PC,xPSR */ + return (U32 *)(p_TCB->tsk_stack + 8*4); + } +#else + /* Stack Frame: R4-R11,R0-R3,R12,LR,PC,xPSR */ + return (U32 *)(p_TCB->tsk_stack + 8*4); +#endif +} + +void rt_ret_val (P_TCB p_TCB, U32 v0) { + U32 *ret; + + ret = rt_ret_regs(p_TCB); + ret[0] = v0; +} + +void rt_ret_val2(P_TCB p_TCB, U32 v0, U32 v1) { + U32 *ret; + + ret = rt_ret_regs(p_TCB); + ret[0] = v0; + ret[1] = v1; +} + + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/RTX_CM_lib.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/RTX_CM_lib.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,388 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RTX_CM_LIB.H + * Purpose: RTX Kernel System Configuration + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#if defined (__CC_ARM) +#pragma O3 +#define __USED __attribute__((used)) +#elif defined (__GNUC__) +#pragma GCC optimize ("O3") +#define __USED __attribute__((used)) +#elif defined (__ICCARM__) +#define __USED __root +#endif + + +/*---------------------------------------------------------------------------- + * Definitions + *---------------------------------------------------------------------------*/ + +#define _declare_box(pool,size,cnt) uint32_t pool[(((size)+3)/4)*(cnt) + 3] +#define _declare_box8(pool,size,cnt) uint64_t pool[(((size)+7)/8)*(cnt) + 2] + +#define OS_TCB_SIZE 48 +#define OS_TMR_SIZE 8 + +#if defined (__CC_ARM) && !defined (__MICROLIB) + +typedef void *OS_ID; +typedef uint32_t OS_TID; +typedef uint32_t OS_MUT[3]; +typedef uint32_t OS_RESULT; + +#define runtask_id() rt_tsk_self() +#define mutex_init(m) rt_mut_init(m) +#define mutex_wait(m) os_mut_wait(m,0xFFFF) +#define mutex_rel(m) os_mut_release(m) + +extern OS_TID rt_tsk_self (void); +extern void rt_mut_init (OS_ID mutex); +extern OS_RESULT rt_mut_release (OS_ID mutex); +extern OS_RESULT rt_mut_wait (OS_ID mutex, uint16_t timeout); + +#define os_mut_wait(mutex,timeout) _os_mut_wait((uint32_t)rt_mut_wait,mutex,timeout) +#define os_mut_release(mutex) _os_mut_release((uint32_t)rt_mut_release,mutex) + +OS_RESULT _os_mut_release (uint32_t p, OS_ID mutex) __svc_indirect(0); +OS_RESULT _os_mut_wait (uint32_t p, OS_ID mutex, uint16_t timeout) __svc_indirect(0); + +#endif + + +/*---------------------------------------------------------------------------- + * Global Variables + *---------------------------------------------------------------------------*/ + +#if (OS_TIMERS != 0) +#define OS_TASK_CNT (OS_TASKCNT + 1) +#define OS_PRIV_CNT (OS_PRIVCNT + 2) +#define OS_STACK_SZ (4*(OS_PRIVSTKSIZE+OS_MAINSTKSIZE+OS_TIMERSTKSZ)) +#else +#define OS_TASK_CNT OS_TASKCNT +#define OS_PRIV_CNT (OS_PRIVCNT + 1) +#define OS_STACK_SZ (4*(OS_PRIVSTKSIZE+OS_MAINSTKSIZE)) +#endif + +uint16_t const os_maxtaskrun = OS_TASK_CNT; +uint32_t const os_stackinfo = (OS_STKCHECK<<24)| (OS_PRIV_CNT<<16) | (OS_STKSIZE*4); +uint32_t const os_rrobin = (OS_ROBIN << 16) | OS_ROBINTOUT; +uint32_t const os_trv = OS_TRV; +uint8_t const os_flags = OS_RUNPRIV; + +/* Export following defines to uVision debugger. */ +__USED uint32_t const os_clockrate = OS_TICK; +__USED uint32_t const os_timernum = 0; + +/* Memory pool for TCB allocation */ +_declare_box (mp_tcb, OS_TCB_SIZE, OS_TASK_CNT); +uint16_t const mp_tcb_size = sizeof(mp_tcb); + +/* Memory pool for System stack allocation (+os_idle_demon). */ +_declare_box8 (mp_stk, OS_STKSIZE*4, OS_TASK_CNT-OS_PRIV_CNT+1); +uint32_t const mp_stk_size = sizeof(mp_stk); + +/* Memory pool for user specified stack allocation (+main, +timer) */ +uint64_t os_stack_mem[2+OS_PRIV_CNT+(OS_STACK_SZ/8)]; +uint32_t const os_stack_sz = sizeof(os_stack_mem); + +#ifndef OS_FIFOSZ + #define OS_FIFOSZ 16 +#endif + +/* Fifo Queue buffer for ISR requests.*/ +uint32_t os_fifo[OS_FIFOSZ*2+1]; +uint8_t const os_fifo_size = OS_FIFOSZ; + +/* An array of Active task pointers. */ +void *os_active_TCB[OS_TASK_CNT]; + +/* User Timers Resources */ +#if (OS_TIMERS != 0) +extern void osTimerThread (void const *argument); +#if defined (__MBED_CMSIS_RTOS_CA9) +osThreadDef(osTimerThread, (osPriority)(OS_TIMERPRIO-3), 4*OS_TIMERSTKSZ); +#else +osThreadDef(osTimerThread, (osPriority)(OS_TIMERPRIO-3), 1, 4*OS_TIMERSTKSZ); +#endif +osThreadId osThreadId_osTimerThread; +osMessageQDef(osTimerMessageQ, OS_TIMERCBQS, void *); +osMessageQId osMessageQId_osTimerMessageQ; +#else +osThreadDef_t os_thread_def_osTimerThread = { NULL }; +osThreadId osThreadId_osTimerThread; +osMessageQDef(osTimerMessageQ, 0, void *); +osMessageQId osMessageQId_osTimerMessageQ; +#endif + +/* Legacy RTX User Timers not used */ +uint32_t os_tmr = 0; +uint32_t const *m_tmr = NULL; +uint16_t const mp_tmr_size = 0; + +#if defined (__CC_ARM) && !defined (__MICROLIB) + /* A memory space for arm standard library. */ + static uint32_t std_libspace[OS_TASK_CNT][96/4]; + static OS_MUT std_libmutex[OS_MUTEXCNT]; + static uint32_t nr_mutex; + extern void *__libspace_start; +#endif + + +/*---------------------------------------------------------------------------- + * RTX Optimizations (empty functions) + *---------------------------------------------------------------------------*/ + +#if OS_ROBIN == 0 + void rt_init_robin (void) {;} + void rt_chk_robin (void) {;} +#endif + +#if OS_STKCHECK == 0 + void rt_stk_check (void) {;} +#endif + + +/*---------------------------------------------------------------------------- + * Standard Library multithreading interface + *---------------------------------------------------------------------------*/ + +#if defined (__CC_ARM) && !defined (__MICROLIB) + +/*--------------------------- __user_perthread_libspace ---------------------*/ + +void *__user_perthread_libspace (void) { + /* Provide a separate libspace for each task. */ + uint32_t idx; + + idx = runtask_id (); + if (idx == 0) { + /* RTX not running yet. */ + return (&__libspace_start); + } + return ((void *)&std_libspace[idx-1]); +} + +/*--------------------------- _mutex_initialize -----------------------------*/ + +int _mutex_initialize (OS_ID *mutex) { + /* Allocate and initialize a system mutex. */ + + if (nr_mutex >= OS_MUTEXCNT) { + /* If you are here, you need to increase the number OS_MUTEXCNT. */ + for (;;); + } + *mutex = &std_libmutex[nr_mutex++]; + mutex_init (*mutex); + return (1); +} + + +/*--------------------------- _mutex_acquire --------------------------------*/ + +__attribute__((used)) void _mutex_acquire (OS_ID *mutex) { + /* Acquire a system mutex, lock stdlib resources. */ + if (runtask_id ()) { + /* RTX running, acquire a mutex. */ + mutex_wait (*mutex); + } +} + + +/*--------------------------- _mutex_release --------------------------------*/ + +__attribute__((used)) void _mutex_release (OS_ID *mutex) { + /* Release a system mutex, unlock stdlib resources. */ + if (runtask_id ()) { + /* RTX running, release a mutex. */ + mutex_rel (*mutex); + } +} + +#endif + + +/*---------------------------------------------------------------------------- + * RTX Startup + *---------------------------------------------------------------------------*/ + +/* Main Thread definition */ +extern int main (void); +osThreadDef_t os_thread_def_main = {(os_pthread)main, osPriorityNormal, 1, 4*OS_MAINSTKSIZE }; + + +#if defined (__CC_ARM) + +#ifdef __MICROLIB +void _main_init (void) __attribute__((section(".ARM.Collect$$$$000000FF"))); +#if __TARGET_ARCH_ARM +#pragma push +#pragma arm +#endif +void _main_init (void) { + osKernelInitialize(); + osThreadCreate(&os_thread_def_main, NULL); + osKernelStart(); + for (;;); +} +#if __TARGET_ARCH_ARM +#pragma pop +#endif +#else +__asm void __rt_entry (void) { + + IMPORT __user_setup_stackheap + IMPORT __rt_lib_init + IMPORT os_thread_def_main + IMPORT osKernelInitialize + IMPORT osKernelStart + IMPORT osThreadCreate + IMPORT exit + + BL __user_setup_stackheap + MOV R1,R2 + BL __rt_lib_init + BL osKernelInitialize + LDR R0,=os_thread_def_main + MOVS R1,#0 + BL osThreadCreate + BL osKernelStart + BL exit + + ALIGN +} +#endif + +#elif defined (__GNUC__) + +#ifdef __CS3__ + +/* CS3 start_c routine. + * + * Copyright (c) 2006, 2007 CodeSourcery Inc + * + * The authors hereby grant permission to use, copy, modify, distribute, + * and license this software and its documentation for any purpose, provided + * that existing copyright notices are retained in all copies and that this + * notice is included verbatim in any distributions. No written agreement, + * license, or royalty fee is required for any of the authorized uses. + * Modifications to this software may be copyrighted by their authors + * and need not follow the licensing terms described here, provided that + * the new terms are clearly indicated on the first page of each file where + * they apply. + */ + +#include "cs3.h" + +extern void __libc_init_array (void); + +__attribute ((noreturn)) void __cs3_start_c (void){ + unsigned regions = __cs3_region_num; + const struct __cs3_region *rptr = __cs3_regions; + + /* Initialize memory */ + for (regions = __cs3_region_num, rptr = __cs3_regions; regions--; rptr++) { + long long *src = (long long *)rptr->init; + long long *dst = (long long *)rptr->data; + unsigned limit = rptr->init_size; + unsigned count; + + if (src != dst) + for (count = 0; count != limit; count += sizeof (long long)) + *dst++ = *src++; + else + dst = (long long *)((char *)dst + limit); + limit = rptr->zero_size; + for (count = 0; count != limit; count += sizeof (long long)) + *dst++ = 0; + } + + /* Run initializers. */ + __libc_init_array (); + + osKernelInitialize(); + osThreadCreate(&os_thread_def_main, NULL); + osKernelStart(); + for (;;); +} + +#else + +__attribute__((naked)) void software_init_hook (void) { + __asm ( + ".syntax unified\n" + ".arm\n" + "movs r0,#0\n" + "movs r1,#0\n" + "mov r4,r0\n" + "mov r5,r1\n" + "ldr r0,= __libc_fini_array\n" + "bl atexit\n" + "bl __libc_init_array\n" + "mov r0,r4\n" + "mov r1,r5\n" + "bl osKernelInitialize\n" + "ldr r0,=os_thread_def_main\n" + "movs r1,#0\n" + "bl osThreadCreate\n" + "bl osKernelStart\n" + "bl exit\n" + ); +} + +#endif + +#elif defined (__ICCARM__) + +extern int __low_level_init(void); +extern void __iar_data_init3(void); +extern void exit(int arg); + +__noreturn __stackless void __cmain(void) { + int a; + + if (__low_level_init() != 0) { + __iar_data_init3(); + } + osKernelInitialize(); + osThreadCreate(&os_thread_def_main, NULL); + a = osKernelStart(); + exit(a); +} + +#endif + + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/RTX_Conf_CA.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/RTX_Conf_CA.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,319 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RTX_Conf_CM.C + * Purpose: Configuration of CMSIS RTX Kernel + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2013 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "cmsis_os.h" + +/*---------------------------------------------------------------------------- + * RTX User configuration part BEGIN + *---------------------------------------------------------------------------*/ + +//-------- <<< Use Configuration Wizard in Context Menu >>> ----------------- +// +// <h>Thread Configuration +// ======================= +// +// <o>Number of concurrent running threads <0-250> +// <i> Defines max. number of threads that will run at the same time. +// <i> Default: 6 +#ifndef OS_TASKCNT + #define OS_TASKCNT 25 +#endif + +// <o>Default Thread stack size [bytes] <64-4096:8><#/4> +// <i> Defines default stack size for threads with osThreadDef stacksz = 0 +// <i> Default: 200 +#ifndef OS_STKSIZE + #define OS_STKSIZE 200 +#endif + +// <o>Main Thread stack size [bytes] <64-4096:8><#/4> +// <i> Defines stack size for main thread. +// <i> Default: 200 +#ifndef OS_MAINSTKSIZE + #define OS_MAINSTKSIZE 512 +#endif + +// <o>Number of threads with user-provided stack size <0-250> +// <i> Defines the number of threads with user-provided stack size. +// <i> Default: 0 +#ifndef OS_PRIVCNT + #define OS_PRIVCNT 10 +#endif + +// <o>Total stack size [bytes] for threads with user-provided stack size <0-4096:8><#/4> +// <i> Defines the combined stack size for threads with user-provided stack size. +// <i> Default: 0 +#ifndef OS_PRIVSTKSIZE + #define OS_PRIVSTKSIZE 8192 +#endif + +// <q>Check for stack overflow +// <i> Includes the stack checking code for stack overflow. +// <i> Note that additional code reduces the Kernel performance. +#ifndef OS_STKCHECK + #define OS_STKCHECK 1 +#endif + +// <o>Processor mode for thread execution +// <0=> Unprivileged mode +// <1=> Privileged mode +// <i> Default: Privileged mode +#ifndef OS_RUNPRIV + #define OS_RUNPRIV 1 +#endif + +// </h> + +// <h>RTX Kernel Timer Tick Configuration +// ====================================== +// <q> Use Cortex-M SysTick timer as RTX Kernel Timer +// <i> Use the Cortex-M SysTick timer as a time-base for RTX. +#ifndef OS_SYSTICK + #define OS_SYSTICK 0 +#endif +// +// <o>Timer clock value [Hz] <1-1000000000> +// <i> Defines the timer clock value. +// <i> Default: 12000000 (12MHz) +#ifndef OS_CLOCK +# if defined(TARGET_RZ_A1H) + #define OS_CLOCK 12000000 +# else +# error "no target defined" +# endif +#endif + +// <o>Timer tick value [us] <1-1000000> +// <i> Defines the timer tick value. +// <i> Default: 1000 (1ms) +#ifndef OS_TICK + #define OS_TICK 1000 +#endif + +// </h> + +// <h>System Configuration +// ======================= +// +// <e>Round-Robin Thread switching +// =============================== +// +// <i> Enables Round-Robin Thread switching. +#ifndef OS_ROBIN + #define OS_ROBIN 1 +#endif + +// <o>Round-Robin Timeout [ticks] <1-1000> +// <i> Defines how long a thread will execute before a thread switch. +// <i> Default: 5 +#ifndef OS_ROBINTOUT + #define OS_ROBINTOUT 5 +#endif + +// </e> + +// <e>User Timers +// ============== +// <i> Enables user Timers +#ifndef OS_TIMERS + #define OS_TIMERS 1 +#endif + +// <o>Timer Thread Priority +// <1=> Low +// <2=> Below Normal <3=> Normal <4=> Above Normal +// <5=> High +// <6=> Realtime (highest) +// <i> Defines priority for Timer Thread +// <i> Default: High +#ifndef OS_TIMERPRIO + #define OS_TIMERPRIO 5 +#endif + +// <o>Timer Thread stack size [bytes] <64-4096:8><#/4> +// <i> Defines stack size for Timer thread. +// <i> Default: 200 +#ifndef OS_TIMERSTKSZ + #define OS_TIMERSTKSZ WORDS_STACK_SIZE +#endif + +// <o>Timer Callback Queue size <1-32> +// <i> Number of concurrent active timer callback functions. +// <i> Default: 4 +#ifndef OS_TIMERCBQS + #define OS_TIMERCBQS 4 +#endif + +// </e> + +// <o>ISR FIFO Queue size<4=> 4 entries <8=> 8 entries +// <12=> 12 entries <16=> 16 entries +// <24=> 24 entries <32=> 32 entries +// <48=> 48 entries <64=> 64 entries +// <96=> 96 entries +// <i> ISR functions store requests to this buffer, +// <i> when they are called from the interrupt handler. +// <i> Default: 16 entries +#ifndef OS_FIFOSZ + #define OS_FIFOSZ 16 +#endif + +// </h> + +//------------- <<< end of configuration section >>> ----------------------- + +// Standard library system mutexes +// =============================== +// Define max. number system mutexes that are used to protect +// the arm standard runtime library. For microlib they are not used. +#ifndef OS_MUTEXCNT + #define OS_MUTEXCNT 12 +#endif + +/*---------------------------------------------------------------------------- + * RTX User configuration part END + *---------------------------------------------------------------------------*/ + +#define OS_TRV ((uint32_t)(((double)OS_CLOCK*(double)OS_TICK)/1E6)-1) + + +/*---------------------------------------------------------------------------- + * Global Functions + *---------------------------------------------------------------------------*/ + +/*--------------------------- os_idle_demon ---------------------------------*/ + +void os_idle_demon (void) { + /* The idle demon is a system thread, running when no other thread is */ + /* ready to run. */ + + for (;;) { + /* HERE: include optional user code to be executed when no thread runs.*/ + } +} + +#if (OS_SYSTICK == 0) // Functions for alternative timer as RTX kernel timer + +/*--------------------------- os_tick_init ----------------------------------*/ +#ifdef TARGET_RZ_A1H +#define OSTM0 (0xFCFEC000uL) /* OSTM0 */ +#define OSTM1 (0xFCFEC400uL) /* OSTM1 */ +#define CPG (0xFCFE0410uL) /* CPG */ + +#define CPGSTBCR5 (*((volatile unsigned char*)(CPG + 0x00000018uL))) + +#define OSTM0CMP (*((volatile unsigned long*)(OSTM0 + 0x00000000uL))) +#define OSTM0CNT (*((volatile unsigned long*)(OSTM0 + 0x00000004uL))) +#define OSTM0TE (*((volatile unsigned char*)(OSTM0 + 0x00000010uL))) +#define OSTM0TS (*((volatile unsigned char*)(OSTM0 + 0x00000014uL))) +#define OSTM0TT (*((volatile unsigned char*)(OSTM0 + 0x00000018uL))) +#define OSTM0CTL (*((volatile unsigned char*)(OSTM0 + 0x00000020uL))) + +#define OSTM1CMP (*((volatile unsigned long*)(OSTM1 + 0x00000000uL))) +#define OSTM1CNT (*((volatile unsigned long*)(OSTM1 + 0x00000004uL))) +#define OSTM1TE (*((volatile unsigned char*)(OSTM1 + 0x00000010uL))) +#define OSTM1TS (*((volatile unsigned char*)(OSTM1 + 0x00000014uL))) +#define OSTM1TT (*((volatile unsigned char*)(OSTM1 + 0x00000018uL))) +#define OSTM1CTL (*((volatile unsigned char*)(OSTM1 + 0x00000020uL))) + +#define CPG_STBCR5_BIT_MSTP51 (0x02u) /* OSTM0 */ +#define CM1_RENESAS_RZ_A1_P0_CLK ( 32000000u) +#define CM0_RENESAS_RZ_A1_P0_CLK ( 33333333u) + +typedef enum +{ + IRQ_SGI0 = 0, + IRQ_OSTMI0TINT = 134 +} IRQn_Type; + +typedef void(*IRQHandler)(); + +extern void PendSV_Handler(uint32_t); +extern void OS_Tick_Handler(uint32_t); +extern uint32_t InterruptHandlerRegister (IRQn_Type irq, IRQHandler handler); +#endif + +// Initialize alternative hardware timer as RTX kernel timer +// Return: IRQ number of the alternative hardware timer +int os_tick_init (void) { +#ifdef TARGET_RZ_A1H + CPGSTBCR5 &= ~(CPG_STBCR5_BIT_MSTP51); /* enable OSTM0 clock */ + + OSTM0TT = 0x1; /* Stop the counter and clears the OSTM0TE bit. */ + OSTM0CTL = 0x1; /* Interval timer mode. Interrupt enabled */ + + OSTM0CMP = (uint32_t)(((double)CM0_RENESAS_RZ_A1_P0_CLK*(double)OS_TICK)/1E6); + + OSTM0TS = 0x1; /* Start the counter and sets the OSTM0TE bit. */ + + InterruptHandlerRegister(IRQ_SGI0 , (IRQHandler)PendSV_Handler); + InterruptHandlerRegister(IRQ_OSTMI0TINT, (IRQHandler)OS_Tick_Handler); + + + return IRQ_OSTMI0TINT; /* Return IRQ number of timer (0..239) */ + /* RTX will set and configure the interrupt */ +#endif +} + +/*--------------------------- os_tick_irqack --------------------------------*/ + +// Acknowledge alternative hardware timer interrupt +void os_tick_irqack (void) { + /* ... */ +} + +#endif // (OS_SYSTICK == 0) + +/*--------------------------- os_error --------------------------------------*/ +extern void mbed_die(void); + +void os_error (uint32_t err_code) { + /* This function is called when a runtime error is detected. Parameter */ + /* 'err_code' holds the runtime error code (defined in RTL.H). */ + mbed_die(); + + /* HERE: include optional code to be executed on runtime error. */ + for (;;); +} + + +/*---------------------------------------------------------------------------- + * RTX Configuration Functions + *---------------------------------------------------------------------------*/ + +#include "RTX_CM_lib.h" + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/RTX_Config.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/RTX_Config.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,76 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RTX_CONFIG.H + * Purpose: Exported functions of RTX_Config.c + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + + +/* Error Codes */ +#define OS_ERR_STK_OVF 1 +#define OS_ERR_FIFO_OVF 2 +#define OS_ERR_MBX_OVF 3 + +/* Definitions */ +#define BOX_ALIGN_8 0x80000000 +#define _declare_box(pool,size,cnt) U32 pool[(((size)+3)/4)*(cnt) + 3] +#define _declare_box8(pool,size,cnt) U64 pool[(((size)+7)/8)*(cnt) + 2] +#define _init_box8(pool,size,bsize) _init_box (pool,size,(bsize) | BOX_ALIGN_8) + +/* Variables */ +extern U32 mp_tcb[]; +extern U64 mp_stk[]; +extern U32 os_fifo[]; +extern void *os_active_TCB[]; + +/* Constants */ +extern U16 const os_maxtaskrun; +extern U32 const os_trv; +extern U8 const os_flags; +extern U32 const os_stackinfo; +extern U32 const os_rrobin; +extern U32 const os_clockrate; +extern U32 const os_timernum; +extern U16 const mp_tcb_size; +extern U32 const mp_stk_size; +extern U32 const *m_tmr; +extern U16 const mp_tmr_size; +extern U8 const os_fifo_size; + +/* Functions */ +extern void os_idle_demon (void); +extern int os_tick_init (void); +extern void os_tick_irqack (void); +extern void os_tmr_call (U16 info); +extern void os_error (U32 err_code); + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/TOOLCHAIN_ARM/HAL_CA9.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/TOOLCHAIN_ARM/HAL_CA9.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,416 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: HAL_CA9.c + * Purpose: Hardware Abstraction Layer for Cortex-A9 + * Rev.: 3 Sept 2013 + *---------------------------------------------------------------------------- + * + * Copyright (c) 2012 - 2013 ARM Limited + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_System.h" +#include "rt_Task.h" +#include "rt_List.h" +#include "rt_MemBox.h" +#include "rt_HAL_CA.h" + + +/*---------------------------------------------------------------------------- + * Functions + *---------------------------------------------------------------------------*/ + +//For A-class, set USR/SYS stack +__asm void rt_set_PSP (U32 stack) { + ARM + + MRS R1, CPSR + CPS #MODE_SYS ;no effect in USR mode + ISB + MOV SP, R0 + MSR CPSR_c, R1 ;no effect in USR mode + ISB + BX LR + +} + +//For A-class, get USR/SYS stack +__asm U32 rt_get_PSP (void) { + ARM + + MRS R1, CPSR + CPS #MODE_SYS ;no effect in USR mode + ISB + MOV R0, SP + MSR CPSR_c, R1 ;no effect in USR mode + ISB + BX LR +} + +/*--------------------------- _alloc_box ------------------------------------*/ +__asm void *_alloc_box (void *box_mem) { + /* Function wrapper for Unprivileged/Privileged mode. */ + ARM + + LDR R12,=__cpp(rt_alloc_box) + MRS R2, CPSR + LSLS R2, #28 + BXNE R12 + SVC 0 + BX LR +} + + +/*--------------------------- _free_box -------------------------------------*/ +__asm int _free_box (void *box_mem, void *box) { + /* Function wrapper for Unprivileged/Privileged mode. */ + ARM + + LDR R12,=__cpp(rt_free_box) + MRS R2, CPSR + LSLS R2, #28 + BXNE R12 + SVC 0 + BX LR + +} + +/*-------------------------- SVC_Handler -----------------------------------*/ + +#pragma push +#pragma arm +__asm void SVC_Handler (void) { + PRESERVE8 + ARM + + IMPORT rt_tsk_lock + IMPORT rt_tsk_unlock + IMPORT SVC_Count + IMPORT SVC_Table + IMPORT rt_stk_check + IMPORT FPUEnable + +Mode_SVC EQU 0x13 + + SRSFD SP!, #Mode_SVC ; Push LR_SVC and SPRS_SVC onto SVC mode stack + PUSH {R4} ; Push R4 so we can use it as a temp + + MRS R4,SPSR ; Get SPSR + TST R4,#CPSR_T_BIT ; Check Thumb Bit + LDRNEH R4,[LR,#-2] ; Thumb: Load Halfword + BICNE R4,R4,#0xFF00 ; Extract SVC Number + LDREQ R4,[LR,#-4] ; ARM: Load Word + BICEQ R4,R4,#0xFF000000 ; Extract SVC Number + + /* Lock out systick and re-enable interrupts */ + PUSH {R0-R3,R12,LR} + + AND R12, SP, #4 ; Ensure stack is 8-byte aligned + SUB SP, SP, R12 ; Adjust stack + PUSH {R12, LR} ; Store stack adjustment and dummy LR to SVC stack + + BLX rt_tsk_lock + CPSIE i + + POP {R12, LR} ; Get stack adjustment & discard dummy LR + ADD SP, SP, R12 ; Unadjust stack + + POP {R0-R3,R12,LR} + + CMP R4,#0 + BNE SVC_User + + MRS R4,SPSR + PUSH {R4} ; Push R4 so we can use it as a temp + AND R4, SP, #4 ; Ensure stack is 8-byte aligned + SUB SP, SP, R4 ; Adjust stack + PUSH {R4, LR} ; Store stack adjustment and dummy LR + BLX R12 + POP {R4, LR} ; Get stack adjustment & discard dummy LR + ADD SP, SP, R4 ; Unadjust stack + POP {R4} ; Restore R4 + MSR SPSR_CXSF,R4 + + /* Here we will be in SVC mode (even if coming in from PendSV_Handler or OS_Tick_Handler) */ +Sys_Switch + LDR LR,=__cpp(&os_tsk) + LDM LR,{R4,LR} ; os_tsk.run, os_tsk.new + CMP R4,LR + BNE switching + + PUSH {R0-R3,R12,LR} + + AND R12, SP, #4 ; Ensure stack is 8-byte aligned + SUB SP, SP, R12 ; Adjust stack + PUSH {R12, LR} ; Store stack adjustment and dummy LR to SVC stack + + CPSID i + BLX rt_tsk_unlock + + POP {R12, LR} ; Get stack adjustment & discard dummy LR + ADD SP, SP, R12 ; Unadjust stack + + POP {R0-R3,R12,LR} + POP {R4} + RFEFD SP! ; Return from exception, no task switch + +switching + CLREX + CMP R4,#0 + ADDEQ SP,SP,#12 ; Original R4, LR & SPSR do not need to be popped when we are paging in a different task + BEQ SVC_Next ; Runtask deleted? + + + PUSH {R8-R11} //R4 and LR already stacked + MOV R10,R4 ; Preserve os_tsk.run + MOV R11,LR ; Preserve os_tsk.new + + ADD R8,SP,#16 ; Unstack R4,LR + LDMIA R8,{R4,LR} + + SUB SP,SP,#4 ; Make space on the stack for the next instn + STMIA SP,{SP}^ ; Put User SP onto stack + POP {R8} ; Pop User SP into R8 + + MRS R9,SPSR + STMDB R8!,{R9} ; User CPSR + STMDB R8!,{LR} ; User PC + STMDB R8,{LR}^ ; User LR + SUB R8,R8,#4 ; No writeback for store of User LR + STMDB R8!,{R0-R3,R12} ; User R0-R3,R12 + MOV R3,R10 ; os_tsk.run + MOV LR,R11 ; os_tsk.new + POP {R9-R12} + ADD SP,SP,#12 ; Fix up SP for unstack of R4, LR & SPSR + STMDB R8!,{R4-R7,R9-R12} ; User R4-R11 + + //If applicable, stack VFP state + MRC p15,0,R1,c1,c0,2 ; VFP/NEON access enabled? (CPACR) + AND R2,R1,#0x00F00000 + CMP R2,#0x00F00000 + BNE no_outgoing_vfp + VMRS R2,FPSCR + STMDB R8!,{R2,R4} ; Push FPSCR, maintain 8-byte alignment + VSTMDB R8!,{S0-S31} + LDRB R2,[R3,#TCB_STACKF] ; Record in TCB that VFP state is stacked + ORR R2,#2 + STRB R2,[R3,#TCB_STACKF] + +no_outgoing_vfp + STR R8,[R3,#TCB_TSTACK] + MOV R4,LR + + PUSH {R4} ; Push R4 so we can use it as a temp + AND R4, SP, #4 ; Ensure stack is 8-byte aligned + SUB SP, SP, R4 ; Adjust stack + PUSH {R4, LR} ; Store stack adjustment and dummy LR to SVC stack + + BLX rt_stk_check + + POP {R4, LR} ; Get stack adjustment & discard dummy LR + ADD SP, SP, R4 ; Unadjust stack + POP {R4} ; Restore R4 + + MOV LR,R4 + +SVC_Next //R4 == os_tsk.run, LR == os_tsk.new, R0-R3, R5-R12 corruptible + LDR R1,=__cpp(&os_tsk) ; os_tsk.run = os_tsk.new + STR LR,[R1] + LDRB R1,[LR,#TCB_TID] ; os_tsk.run->task_id + LSL R1,#8 ; Store PROCID + MCR p15,0,R1,c13,c0,1 ; Write CONTEXTIDR + + LDR R0,[LR,#TCB_TSTACK] ; os_tsk.run->tsk_stack + + //Does incoming task have VFP state in stack? + LDRB R3,[LR,#TCB_STACKF] + TST R3,#0x2 + MRC p15,0,R1,c1,c0,2 ; Read CPACR + ANDEQ R1,R1,#0xFF0FFFFF ; Disable VFP access if incoming task does not have stacked VFP state + ORRNE R1,R1,#0x00F00000 ; Enable VFP access if incoming task does have stacked VFP state + MCR p15,0,R1,c1,c0,2 ; Write CPACR + BEQ no_incoming_vfp + ISB ; We only need the sync if we enabled, otherwise we will context switch before next VFP instruction anyway + VLDMIA R0!,{S0-S31} + LDR R2,[R0] + VMSR FPSCR,R2 + ADD R0,R0,#8 + +no_incoming_vfp + LDR R1,[R0,#60] ; Restore User CPSR + MSR SPSR_CXSF,R1 + LDMIA R0!,{R4-R11} ; Restore User R4-R11 + ADD R0,R0,#4 ; Restore User R1-R3,R12 + LDMIA R0!,{R1-R3,R12} + LDMIA R0,{LR}^ ; Restore User LR + ADD R0,R0,#4 ; No writeback for load to user LR + LDMIA R0!,{LR} ; Restore User PC + ADD R0,R0,#4 ; Correct User SP for unstacked user CPSR + + PUSH {R0} ; Push R0 onto stack + LDMIA SP,{SP}^ ; Get R0 off stack into User SP + ADD SP,SP,#4 ; Put SP back + + LDR R0,[R0,#-32] ; Restore R0 + + PUSH {R0-R3,R12,LR} + + AND R12, SP, #4 ; Ensure stack is 8-byte aligned + SUB SP, SP, R12 ; Adjust stack + PUSH {R12, LR} ; Store stack adjustment and dummy LR to SVC stack + + CPSID i + BLX rt_tsk_unlock + + POP {R12, LR} ; Get stack adjustment & discard dummy LR + ADD SP, SP, R12 ; Unadjust stack + + POP {R0-R3,R12,LR} + + MOVS PC,LR ; Return from exception + + + /*------------------- User SVC -------------------------------*/ + +SVC_User + LDR R12,=SVC_Count + LDR R12,[R12] + CMP R4,R12 ; Check for overflow + BHI SVC_Done + + LDR R12,=SVC_Table-4 + LDR R12,[R12,R4,LSL #2] ; Load SVC Function Address + MRS R4,SPSR ; Save SPSR + PUSH {R4} ; Push R4 so we can use it as a temp + AND R4, SP, #4 ; Ensure stack is 8-byte aligned + SUB SP, SP, R4 ; Adjust stack + PUSH {R4, LR} ; Store stack adjustment and dummy LR + BLX R12 ; Call SVC Function + POP {R4, LR} ; Get stack adjustment & discard dummy LR + ADD SP, SP, R4 ; Unadjust stack + POP {R4} ; Restore R4 + MSR SPSR_CXSF,R4 ; Restore SPSR + +SVC_Done + PUSH {R0-R3,R12,LR} + + PUSH {R4} ; Push R4 so we can use it as a temp + AND R4, SP, #4 ; Ensure stack is 8-byte aligned + SUB SP, SP, R4 ; Adjust stack + PUSH {R4, LR} ; Store stack adjustment and dummy LR + + CPSID i + BLX rt_tsk_unlock + + POP {R4, LR} ; Get stack adjustment & discard dummy LR + ADD SP, SP, R4 ; Unadjust stack + POP {R4} ; Restore R4 + + POP {R0-R3,R12,LR} + POP {R4} + RFEFD SP! ; Return from exception +} +#pragma pop + +#pragma push +#pragma arm +__asm void PendSV_Handler (U32 IRQn) { + ARM + + IMPORT rt_tsk_lock + IMPORT IRQNestLevel + + ADD SP,SP,#8 //fix up stack pointer (R0 has been pushed and will never be popped, R1 was pushed for stack alignment) + + //Disable systick interrupts, then write EOIR. We want interrupts disabled before we enter the context switcher. + PUSH {R0, R1} + BLX rt_tsk_lock + POP {R0, R1} + LDR R1, =__cpp(&GICInterface_BASE) + LDR R1, [R1, #0] + STR R0, [R1, #0x10] + + LDR R0, =IRQNestLevel ; Get address of nesting counter + LDR R1, [R0] + SUB R1, R1, #1 ; Decrement nesting counter + STR R1, [R0] + + BLX __cpp(rt_pop_req) + + POP {R1, LR} ; Get stack adjustment & discard dummy LR + ADD SP, SP, R1 ; Unadjust stack + + LDR R0,[SP,#24] + MSR SPSR_CXSF,R0 + POP {R0-R3,R12} ; Leave SPSR & LR on the stack + PUSH {R4} + B Sys_Switch +} +#pragma pop + + +#pragma push +#pragma arm +__asm void OS_Tick_Handler (U32 IRQn) { + ARM + + IMPORT rt_tsk_lock + IMPORT IRQNestLevel + + ADD SP,SP,#8 //fix up stack pointer (R0 has been pushed and will never be popped, R1 was pushed for stack alignment) + + PUSH {R0, R1} + BLX rt_tsk_lock + POP {R0, R1} + LDR R1, =__cpp(&GICInterface_BASE) + LDR R1, [R1, #0] + STR R0, [R1, #0x10] + + LDR R0, =IRQNestLevel ; Get address of nesting counter + LDR R1, [R0] + SUB R1, R1, #1 ; Decrement nesting counter + STR R1, [R0] + + BLX __cpp(os_tick_irqack) + BLX __cpp(rt_systick) + + POP {R1, LR} ; Get stack adjustment & discard dummy LR + ADD SP, SP, R1 ; Unadjust stack + + LDR R0,[SP,#24] + MSR SPSR_CXSF,R0 + POP {R0-R3,R12} ; Leave SPSR & LR on the stack + PUSH {R4} + B Sys_Switch +} +#pragma pop + + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/TOOLCHAIN_ARM/SVC_Table.s --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/TOOLCHAIN_ARM/SVC_Table.s Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,57 @@ +;/*---------------------------------------------------------------------------- +; * RL-ARM - RTX +; *---------------------------------------------------------------------------- +; * Name: SVC_TABLE.S +; * Purpose: Pre-defined SVC Table for Cortex-M +; * Rev.: V4.60 +; *---------------------------------------------------------------------------- +; * +; * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH +; * All rights reserved. +; * Redistribution and use in source and binary forms, with or without +; * modification, are permitted provided that the following conditions are met: +; * - Redistributions of source code must retain the above copyright +; * notice, this list of conditions and the following disclaimer. +; * - Redistributions in binary form must reproduce the above copyright +; * notice, this list of conditions and the following disclaimer in the +; * documentation and/or other materials provided with the distribution. +; * - Neither the name of ARM nor the names of its contributors may be used +; * to endorse or promote products derived from this software without +; * specific prior written permission. +; * +; * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +; * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +; * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +; * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE +; * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +; * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +; * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +; * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +; * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +; * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +; * POSSIBILITY OF SUCH DAMAGE. +; *---------------------------------------------------------------------------*/ + + + AREA SVC_TABLE, CODE, READONLY + + EXPORT SVC_Count + +SVC_Cnt EQU (SVC_End-SVC_Table)/4 +SVC_Count DCD SVC_Cnt + +; Import user SVC functions here. +; IMPORT __SVC_1 + + EXPORT SVC_Table +SVC_Table +; Insert user SVC functions here. SVC 0 used by RTL Kernel. +; DCD __SVC_1 ; InitMemorySubsystem + +SVC_End + + END + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/TOOLCHAIN_GCC/HAL_CA9.s --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/TOOLCHAIN_GCC/HAL_CA9.s Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,474 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: HAL_CA9.c + * Purpose: Hardware Abstraction Layer for Cortex-A9 + * Rev.: 3 Sept 2013 + *---------------------------------------------------------------------------- + * + * Copyright (c) 2012 - 2013 ARM Limited + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + + .global rt_set_PSP + .global rt_get_PSP + .global _alloc_box + .global _free_box + .global PendSV_Handler + .global OS_Tick_Handler + + .EQU CPSR_T_BIT, 0x20 + .EQU CPSR_I_BIT, 0x80 + .EQU CPSR_F_BIT, 0x40 + + .EQU MODE_USR, 0x10 + .EQU MODE_FIQ, 0x11 + .EQU MODE_IRQ, 0x12 + .EQU MODE_SVC, 0x13 + .EQU MODE_ABT, 0x17 + .EQU MODE_UND, 0x1B + .EQU MODE_SYS, 0x1F + + .EQU TCB_TID, 3 /* 'task id' offset */ + .EQU TCB_STACKF, 32 /* 'stack_frame' offset */ + .EQU TCB_TSTACK, 36 /* 'tsk_stack' offset */ + + .extern rt_alloc_box + .extern os_tsk + .extern GICInterface_BASE + .extern rt_pop_req + .extern os_tick_irqack + .extern rt_systick + +/*---------------------------------------------------------------------------- + * Functions + *---------------------------------------------------------------------------*/ + .text +@ For A-class, set USR/SYS stack +@ __asm void rt_set_PSP (U32 stack) { +rt_set_PSP: + .arm + + MRS R1, CPSR + CPS #MODE_SYS @no effect in USR mode + ISB + MOV SP, R0 + MSR CPSR_c, R1 @no effect in USR mode + ISB + BX LR + +@ } + +@ For A-class, get USR/SYS stack +@ __asm U32 rt_get_PSP (void) { +rt_get_PSP: + .arm + + MRS R1, CPSR + CPS #MODE_SYS @no effect in USR mode + ISB + MOV R0, SP + MSR CPSR_c, R1 @no effect in USR mode + ISB + BX LR + +@ } + +/*--------------------------- _alloc_box ------------------------------------*/ +@ __asm void *_alloc_box (void *box_mem) { +_alloc_box: + /* Function wrapper for Unprivileged/Privileged mode. */ + .arm + + LDR R12,=rt_alloc_box @ __cpp(rt_alloc_box) + MRS R2, CPSR + LSLS R2, #28 + BXNE R12 + SVC 0 + BX LR +@ } + + +/*--------------------------- _free_box -------------------------------------*/ +@ __asm int _free_box (void *box_mem, void *box) { +_free_box: + /* Function wrapper for Unprivileged/Privileged mode. */ + .arm + + LDR R12,=rt_free_box @ __cpp(rt_free_box) + MRS R2, CPSR + LSLS R2, #28 + BXNE R12 + SVC 0 + BX LR + +@ } + +/*-------------------------- SVC_Handler -----------------------------------*/ + +@ #pragma push +@ #pragma arm +@ __asm void SVC_Handler (void) { + + .type SVC_Handler, %function + .global SVC_Handler +SVC_Handler: +@ PRESERVE8 + .arm + .extern rt_tsk_lock + .extern rt_tsk_unlock + .extern SVC_Count + .extern SVC_Table + .extern rt_stk_check + .extern FPUEnable + + .EQU Mode_SVC, 0x13 + + SRSDB SP!, #Mode_SVC @ Push LR_SVC and SPRS_SVC onto SVC mode stack + PUSH {R4} @ Push R4 so we can use it as a temp + + + MRS R4,SPSR @ Get SPSR + TST R4,#CPSR_T_BIT @ Check Thumb Bit + LDRNEH R4,[LR,#-2] @ Thumb: Load Halfword + BICNE R4,R4,#0xFF00 @ Extract SVC Number + LDREQ R4,[LR,#-4] @ ARM: Load Word + BICEQ R4,R4,#0xFF000000 @ Extract SVC Number + + /* Lock out systick and re-enable interrupts */ + PUSH {R0-R3,R12,LR} + + AND R12, SP, #4 @ Ensure stack is 8-byte aligned + SUB SP, SP, R12 @ Adjust stack + PUSH {R12, LR} @ Store stack adjustment and dummy LR to SVC stack + + BLX rt_tsk_lock + CPSIE i + + POP {R12, LR} @ Get stack adjustment & discard dummy LR + ADD SP, SP, R12 @ Unadjust stack + + POP {R0-R3,R12,LR} + + CMP R4,#0 + BNE SVC_User + + MRS R4,SPSR + PUSH {R4} @ Push R4 so we can use it as a temp + AND R4, SP, #4 @ Ensure stack is 8-byte aligned + SUB SP, SP, R4 @ Adjust stack + PUSH {R4, LR} @ Store stack adjustment and dummy LR + BLX R12 + POP {R4, LR} @ Get stack adjustment & discard dummy LR + ADD SP, SP, R4 @ Unadjust stack + POP {R4} @ Restore R4 + MSR SPSR_cxsf,R4 + + /* Here we will be in SVC mode (even if coming in from PendSV_Handler or OS_Tick_Handler) */ +Sys_Switch: + LDR LR,=os_tsk @ __cpp(&os_tsk) + LDM LR,{R4,LR} @ os_tsk.run, os_tsk.new + CMP R4,LR + BNE switching + + PUSH {R0-R3,R12,LR} + + AND R12, SP, #4 @ Ensure stack is 8-byte aligned + SUB SP, SP, R12 @ Adjust stack + PUSH {R12, LR} @ Store stack adjustment and dummy LR to SVC stack + + CPSID i + BLX rt_tsk_unlock + + POP {R12, LR} @ Get stack adjustment & discard dummy LR + ADD SP, SP, R12 @ Unadjust stack + + POP {R0-R3,R12,LR} + POP {R4} + RFEFD SP! @ Return from exception, no task switch + +switching: + CLREX + CMP R4,#0 + ADDEQ SP,SP,#12 @ Original R4, LR & SPSR do not need to be popped when we are paging in a different task + BEQ SVC_Next @ Runtask deleted? + + + PUSH {R8-R11} @ R4 and LR already stacked + MOV R10,R4 @ Preserve os_tsk.run + MOV R11,LR @ Preserve os_tsk.new + + ADD R8,SP,#16 @ Unstack R4,LR + LDMIA R8,{R4,LR} + + SUB SP,SP,#4 @ Make space on the stack for the next instn + STMIA SP,{SP}^ @ Put User SP onto stack + POP {R8} @ Pop User SP into R8 + + MRS R9,SPSR + STMDB R8!,{R9} @ User CPSR + STMDB R8!,{LR} @ User PC + STMDB R8,{LR}^ @ User LR + SUB R8,R8,#4 @ No writeback for store of User LR + STMDB R8!,{R0-R3,R12} @ User R0-R3,R12 + MOV R3,R10 @ os_tsk.run + MOV LR,R11 @ os_tsk.new + POP {R9-R12} + ADD SP,SP,#12 @ Fix up SP for unstack of R4, LR & SPSR + STMDB R8!,{R4-R7,R9-R12} @ User R4-R11 + + @ If applicable, stack VFP state + MRC p15,0,R1,c1,c0,2 @ VFP/NEON access enabled? (CPACR) + AND R2,R1,#0x00F00000 + CMP R2,#0x00F00000 + BNE no_outgoing_vfp + VMRS R2,FPSCR + STMDB R8!,{R2,R4} @ Push FPSCR, maintain 8-byte alignment + VSTMDB R8!,{S0-S31} + LDRB R2,[R3,#TCB_STACKF] @ Record in TCB that VFP state is stacked + ORR R2,#2 + STRB R2,[R3,#TCB_STACKF] + +no_outgoing_vfp: + STR R8,[R3,#TCB_TSTACK] + MOV R4,LR + + PUSH {R4} @ Push R4 so we can use it as a temp + AND R4, SP, #4 @ Ensure stack is 8-byte aligned + SUB SP, SP, R4 @ Adjust stack + PUSH {R4, LR} @ Store stack adjustment and dummy LR to SVC stack + + BLX rt_stk_check + + POP {R4, LR} @ Get stack adjustment & discard dummy LR + ADD SP, SP, R4 @ Unadjust stack + POP {R4} @ Restore R4 + + MOV LR,R4 + +SVC_Next: @ R4 == os_tsk.run, LR == os_tsk.new, R0-R3, R5-R12 corruptible + LDR R1,=os_tsk @ __cpp(&os_tsk), os_tsk.run = os_tsk.new + STR LR,[R1] + LDRB R1,[LR,#TCB_TID] @ os_tsk.run->task_id + LSL R1,#8 @ Store PROCID + MCR p15,0,R1,c13,c0,1 @ Write CONTEXTIDR + + LDR R0,[LR,#TCB_TSTACK] @ os_tsk.run->tsk_stack + + @ Does incoming task have VFP state in stack? + LDRB R3,[LR,#TCB_STACKF] + TST R3,#0x2 + MRC p15,0,R1,c1,c0,2 @ Read CPACR + ANDEQ R1,R1,#0xFF0FFFFF @ Disable VFP access if incoming task does not have stacked VFP state + ORRNE R1,R1,#0x00F00000 @ Enable VFP access if incoming task does have stacked VFP state + MCR p15,0,R1,c1,c0,2 @ Write CPACR + BEQ no_incoming_vfp + ISB @ We only need the sync if we enabled, otherwise we will context switch before next VFP instruction anyway + VLDMIA R0!,{S0-S31} + LDR R2,[R0] + VMSR FPSCR,R2 + ADD R0,R0,#8 + +no_incoming_vfp: + LDR R1,[R0,#60] @ Restore User CPSR + MSR SPSR_cxsf,R1 + LDMIA R0!,{R4-R11} @ Restore User R4-R11 + ADD R0,R0,#4 @ Restore User R1-R3,R12 + LDMIA R0!,{R1-R3,R12} + LDMIA R0,{LR}^ @ Restore User LR + ADD R0,R0,#4 @ No writeback for load to user LR + LDMIA R0!,{LR} @ Restore User PC + ADD R0,R0,#4 @ Correct User SP for unstacked user CPSR + + PUSH {R0} @ Push R0 onto stack + LDMIA SP,{SP}^ @ Get R0 off stack into User SP + ADD SP,SP,#4 @ Put SP back + + LDR R0,[R0,#-32] @ Restore R0 + + PUSH {R0-R3,R12,LR} + + AND R12, SP, #4 @ Ensure stack is 8-byte aligned + SUB SP, SP, R12 @ Adjust stack + PUSH {R12, LR} @ Store stack adjustment and dummy LR to SVC stack + + CPSID i + BLX rt_tsk_unlock + + POP {R12, LR} @ Get stack adjustment & discard dummy LR + ADD SP, SP, R12 @ Unadjust stack + + POP {R0-R3,R12,LR} + + MOVS PC,LR @ Return from exception + + + /*------------------- User SVC -------------------------------*/ + +SVC_User: + LDR R12,=SVC_Count + LDR R12,[R12] + CMP R4,R12 @ Check for overflow + BHI SVC_Done + + LDR R12,=SVC_Table-4 + LDR R12,[R12,R4,LSL #2] @ Load SVC Function Address + MRS R4,SPSR @ Save SPSR + PUSH {R4} @ Push R4 so we can use it as a temp + AND R4, SP, #4 @ Ensure stack is 8-byte aligned + SUB SP, SP, R4 @ Adjust stack + PUSH {R4, LR} @ Store stack adjustment and dummy LR + BLX R12 @ Call SVC Function + POP {R4, LR} @ Get stack adjustment & discard dummy LR + ADD SP, SP, R4 @ Unadjust stack + POP {R4} @ Restore R4 + MSR SPSR_cxsf,R4 @ Restore SPSR + +SVC_Done: + PUSH {R0-R3,R12,LR} + + PUSH {R4} @ Push R4 so we can use it as a temp + AND R4, SP, #4 @ Ensure stack is 8-byte aligned + SUB SP, SP, R4 @ Adjust stack + PUSH {R4, LR} @ Store stack adjustment and dummy LR + + CPSID i + BLX rt_tsk_unlock + + POP {R4, LR} @ Get stack adjustment & discard dummy LR + ADD SP, SP, R4 @ Unadjust stack + POP {R4} @ Restore R4 + + POP {R0-R3,R12,LR} + POP {R4} + RFEFD SP! @ Return from exception + +@ } + +@ #pragma pop + + +@ #pragma push +@ #pragma arm +@ __asm void PendSV_Handler (U32 IRQn) { +PendSV_Handler: + .arm + + .extern rt_tsk_lock + .extern IRQNestLevel + + ADD SP,SP,#8 @ fix up stack pointer (R0 has been pushed and will never be popped, R1 was pushed for stack alignment) + + @ Disable systick interrupts, then write EOIR. We want interrupts disabled before we enter the context switcher. + PUSH {R0, R1} + BLX rt_tsk_lock + POP {R0, R1} + LDR R1, =GICInterface_BASE @ __cpp(&GICInterface_BASE) + LDR R1, [R1, #0] + STR R0, [R1, #0x10] + + LDR R0, =IRQNestLevel @ Get address of nesting counter + LDR R1, [R0] + SUB R1, R1, #1 @ Decrement nesting counter + STR R1, [R0] + + BLX rt_pop_req @ __cpp(rt_pop_req) + + POP {R1, LR} @ Get stack adjustment & discard dummy LR + ADD SP, SP, R1 @ Unadjust stack + + LDR R0,[SP,#24] + MSR SPSR_cxsf,R0 + POP {R0-R3,R12} @ Leave SPSR & LR on the stack + PUSH {R4} + B Sys_Switch +@ } +@ #pragma pop + +@ #pragma push +@ #pragma arm +@ __asm void OS_Tick_Handler (U32 IRQn) { +OS_Tick_Handler: + .arm + + ADD SP,SP,#8 @ fix up stack pointer (R0 has been pushed and will never be popped, R1 was pushed for stack alignment) + + PUSH {R0, R1} + BLX rt_tsk_lock + POP {R0, R1} + LDR R1, =GICInterface_BASE @ __cpp(&GICInterface_BASE) + LDR R1, [R1, #0] + STR R0, [R1, #0x10] + + LDR R0, =IRQNestLevel @ Get address of nesting counter + LDR R1, [R0] + SUB R1, R1, #1 @ Decrement nesting counter + STR R1, [R0] + + BLX os_tick_irqack @ __cpp(os_tick_irqack) + BLX rt_systick @ __cpp(rt_systick) + + POP {R1, LR} @ Get stack adjustment & discard dummy LR + ADD SP, SP, R1 @ Unadjust stack + + LDR R0,[SP,#24] + MSR SPSR_cxsf,R0 + POP {R0-R3,R12} @ Leave SPSR & LR on the stack + PUSH {R4} + B Sys_Switch +@ } +@ #pragma pop + + .global __set_PSP +@ __STATIC_ASM void __set_PSP(uint32_t topOfProcStack) +@ { +__set_PSP: +@ PRESERVE8 + .arm + + BIC R0, R0, #7 @ensure stack is 8-byte aligned + MRS R1, CPSR + CPS #MODE_SYS @no effect in USR mode + MOV SP, R0 + MSR CPSR_c, R1 @no effect in USR mode + ISB + BX LR + +@ } + + .global __set_CPS_USR +@ __STATIC_ASM void __set_CPS_USR(void) +@ { +__set_CPS_USR: + .arm + + CPS #MODE_USR + BX LR +@ } + + .END +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/TOOLCHAIN_GCC/SVC_Table.s --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/TOOLCHAIN_GCC/SVC_Table.s Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,60 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: SVC_TABLE.S + * Purpose: Pre-defined SVC Table for Cortex-M + * Rev.: V4.70 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2013 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + + + .section SVC_TABLE @, CODE, READONLY + .align 5 + + .global SVC_Count + +.EQU SVC_Cnt, (SVC_End-SVC_Table)/4 + +SVC_Count: + .word SVC_Cnt + +@ Import user SVC functions here. +@ .extern __SVC_1 + .global SVC_Table +SVC_Table: +@ Insert user SVC functions here. SVC 0 used by RTL Kernel. +@ .word __SVC_1 @ InitMemorySubsystem + +@SVC_End +SVC_End: + + .END + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/cmsis_os.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/cmsis_os.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,803 @@ +/* ---------------------------------------------------------------------- + * $Date: 5. June 2012 + * $Revision: V1.01 + * + * Project: CMSIS-RTOS API + * Title: cmsis_os.h RTX header file + * + * Version 0.02 + * Initial Proposal Phase + * Version 0.03 + * osKernelStart added, optional feature: main started as thread + * osSemaphores have standard behavior + * osTimerCreate does not start the timer, added osTimerStart + * osThreadPass is renamed to osThreadYield + * Version 1.01 + * Support for C++ interface + * - const attribute removed from the osXxxxDef_t typedef's + * - const attribute added to the osXxxxDef macros + * Added: osTimerDelete, osMutexDelete, osSemaphoreDelete + * Added: osKernelInitialize + *---------------------------------------------------------------------------- + * + * Copyright (c) 2012 ARM LIMITED + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/** +\page cmsis_os_h Header File Template: cmsis_os.h + +The file \b cmsis_os.h is a template header file for a CMSIS-RTOS compliant Real-Time Operating System (RTOS). +Each RTOS that is compliant with CMSIS-RTOS shall provide a specific \b cmsis_os.h header file that represents +its implementation. + +The file cmsis_os.h contains: + - CMSIS-RTOS API function definitions + - struct definitions for parameters and return types + - status and priority values used by CMSIS-RTOS API functions + - macros for defining threads and other kernel objects + + +<b>Name conventions and header file modifications</b> + +All definitions are prefixed with \b os to give an unique name space for CMSIS-RTOS functions. +Definitions that are prefixed \b os_ are not used in the application code but local to this header file. +All definitions and functions that belong to a module are grouped and have a common prefix, i.e. \b osThread. + +Definitions that are marked with <b>CAN BE CHANGED</b> can be adapted towards the needs of the actual CMSIS-RTOS implementation. +These definitions can be specific to the underlying RTOS kernel. + +Definitions that are marked with <b>MUST REMAIN UNCHANGED</b> cannot be altered. Otherwise the CMSIS-RTOS implementation is no longer +compliant to the standard. Note that some functions are optional and need not to be provided by every CMSIS-RTOS implementation. + + +<b>Function calls from interrupt service routines</b> + +The following CMSIS-RTOS functions can be called from threads and interrupt service routines (ISR): + - \ref osSignalSet + - \ref osSemaphoreRelease + - \ref osPoolAlloc, \ref osPoolCAlloc, \ref osPoolFree + - \ref osMessagePut, \ref osMessageGet + - \ref osMailAlloc, \ref osMailCAlloc, \ref osMailGet, \ref osMailPut, \ref osMailFree + +Functions that cannot be called from an ISR are verifying the interrupt status and return in case that they are called +from an ISR context the status code \b osErrorISR. In some implementations this condition might be caught using the HARD FAULT vector. + +Some CMSIS-RTOS implementations support CMSIS-RTOS function calls from multiple ISR at the same time. +If this is impossible, the CMSIS-RTOS rejects calls by nested ISR functions with the status code \b osErrorISRRecursive. + + +<b>Define and reference object definitions</b> + +With <b>\#define osObjectsExternal</b> objects are defined as external symbols. This allows to create a consistent header file +that is used throughout a project as shown below: + +<i>Header File</i> +\code +#include <cmsis_os.h> // CMSIS RTOS header file + +// Thread definition +extern void thread_sample (void const *argument); // function prototype +osThreadDef (thread_sample, osPriorityBelowNormal, 1, 100); + +// Pool definition +osPoolDef(MyPool, 10, long); +\endcode + + +This header file defines all objects when included in a C/C++ source file. When <b>\#define osObjectsExternal</b> is +present before the header file, the objects are defined as external symbols. A single consistent header file can therefore be +used throughout the whole project. + +<i>Example</i> +\code +#include "osObjects.h" // Definition of the CMSIS-RTOS objects +\endcode + +\code +#define osObjectExternal // Objects will be defined as external symbols +#include "osObjects.h" // Reference to the CMSIS-RTOS objects +\endcode + +*/ + +#ifndef _CMSIS_OS_H +#define _CMSIS_OS_H + +/// \note MUST REMAIN UNCHANGED: \b osCMSIS identifies the CMSIS-RTOS API version. +#define osCMSIS 0x10001 ///< API version (main [31:16] .sub [15:0]) + +/// \note CAN BE CHANGED: \b osCMSIS_KERNEL identifies the underlying RTOS kernel and version number. +#define osCMSIS_RTX ((4<<16)|61) ///< RTOS identification and version (main [31:16] .sub [15:0]) + +/// \note MUST REMAIN UNCHANGED: \b osKernelSystemId shall be consistent in every CMSIS-RTOS. +#define osKernelSystemId "RTX V4.61" ///< RTOS identification string + +#define CMSIS_OS_RTX +#define CMSIS_OS_RTX_CA /* new define for Coretex-A */ + +// The stack space occupied is mainly dependent on the underling C standard library +#if defined(TOOLCHAIN_GCC) || defined(TOOLCHAIN_ARM_STD) +# define WORDS_STACK_SIZE 512 +#elif defined(TOOLCHAIN_ARM_MICRO) +# define WORDS_STACK_SIZE 128 +#endif + +#define DEFAULT_STACK_SIZE (WORDS_STACK_SIZE*4) + +/// \note MUST REMAIN UNCHANGED: \b osFeature_xxx shall be consistent in every CMSIS-RTOS. +#define osFeature_MainThread 1 ///< main thread 1=main can be thread, 0=not available +#define osFeature_Pool 1 ///< Memory Pools: 1=available, 0=not available +#define osFeature_MailQ 1 ///< Mail Queues: 1=available, 0=not available +#define osFeature_MessageQ 1 ///< Message Queues: 1=available, 0=not available +#define osFeature_Signals 16 ///< maximum number of Signal Flags available per thread +#define osFeature_Semaphore 65535 ///< maximum count for \ref osSemaphoreCreate function +#define osFeature_Wait 0 ///< osWait function: 1=available, 0=not available + +#if defined (__CC_ARM) +#define os_InRegs __value_in_regs // Compiler specific: force struct in registers +#else +#define os_InRegs +#endif + +#include <stdint.h> +#include <stddef.h> + +#ifdef __cplusplus +extern "C" +{ +#endif + + +// ==== Enumeration, structures, defines ==== + +/// Priority used for thread control. +/// \note MUST REMAIN UNCHANGED: \b osPriority shall be consistent in every CMSIS-RTOS. +typedef enum { + osPriorityIdle = -3, ///< priority: idle (lowest) + osPriorityLow = -2, ///< priority: low + osPriorityBelowNormal = -1, ///< priority: below normal + osPriorityNormal = 0, ///< priority: normal (default) + osPriorityAboveNormal = +1, ///< priority: above normal + osPriorityHigh = +2, ///< priority: high + osPriorityRealtime = +3, ///< priority: realtime (highest) + osPriorityError = 0x84 ///< system cannot determine priority or thread has illegal priority +} osPriority; + +/// Timeout value. +/// \note MUST REMAIN UNCHANGED: \b osWaitForever shall be consistent in every CMSIS-RTOS. +#define osWaitForever 0xFFFFFFFF ///< wait forever timeout value + +/// Status code values returned by CMSIS-RTOS functions. +/// \note MUST REMAIN UNCHANGED: \b osStatus shall be consistent in every CMSIS-RTOS. +typedef enum { + osOK = 0, ///< function completed; no error or event occurred. + osEventSignal = 0x08, ///< function completed; signal event occurred. + osEventMessage = 0x10, ///< function completed; message event occurred. + osEventMail = 0x20, ///< function completed; mail event occurred. + osEventTimeout = 0x40, ///< function completed; timeout occurred. + osErrorParameter = 0x80, ///< parameter error: a mandatory parameter was missing or specified an incorrect object. + osErrorResource = 0x81, ///< resource not available: a specified resource was not available. + osErrorTimeoutResource = 0xC1, ///< resource not available within given time: a specified resource was not available within the timeout period. + osErrorISR = 0x82, ///< not allowed in ISR context: the function cannot be called from interrupt service routines. + osErrorISRRecursive = 0x83, ///< function called multiple times from ISR with same object. + osErrorPriority = 0x84, ///< system cannot determine priority or thread has illegal priority. + osErrorNoMemory = 0x85, ///< system is out of memory: it was impossible to allocate or reserve memory for the operation. + osErrorValue = 0x86, ///< value of a parameter is out of range. + osErrorOS = 0xFF, ///< unspecified RTOS error: run-time error but no other error message fits. + os_status_reserved = 0x7FFFFFFF ///< prevent from enum down-size compiler optimization. +} osStatus; + + +/// Timer type value for the timer definition. +/// \note MUST REMAIN UNCHANGED: \b os_timer_type shall be consistent in every CMSIS-RTOS. +typedef enum { + osTimerOnce = 0, ///< one-shot timer + osTimerPeriodic = 1 ///< repeating timer +} os_timer_type; + +/// Entry point of a thread. +/// \note MUST REMAIN UNCHANGED: \b os_pthread shall be consistent in every CMSIS-RTOS. +typedef void (*os_pthread) (void const *argument); + +/// Entry point of a timer call back function. +/// \note MUST REMAIN UNCHANGED: \b os_ptimer shall be consistent in every CMSIS-RTOS. +typedef void (*os_ptimer) (void const *argument); + +// >>> the following data type definitions may shall adapted towards a specific RTOS + +/// Thread ID identifies the thread (pointer to a thread control block). +/// \note CAN BE CHANGED: \b os_thread_cb is implementation specific in every CMSIS-RTOS. +typedef struct os_thread_cb *osThreadId; + +/// Timer ID identifies the timer (pointer to a timer control block). +/// \note CAN BE CHANGED: \b os_timer_cb is implementation specific in every CMSIS-RTOS. +typedef struct os_timer_cb *osTimerId; + +/// Mutex ID identifies the mutex (pointer to a mutex control block). +/// \note CAN BE CHANGED: \b os_mutex_cb is implementation specific in every CMSIS-RTOS. +typedef struct os_mutex_cb *osMutexId; + +/// Semaphore ID identifies the semaphore (pointer to a semaphore control block). +/// \note CAN BE CHANGED: \b os_semaphore_cb is implementation specific in every CMSIS-RTOS. +typedef struct os_semaphore_cb *osSemaphoreId; + +/// Pool ID identifies the memory pool (pointer to a memory pool control block). +/// \note CAN BE CHANGED: \b os_pool_cb is implementation specific in every CMSIS-RTOS. +typedef struct os_pool_cb *osPoolId; + +/// Message ID identifies the message queue (pointer to a message queue control block). +/// \note CAN BE CHANGED: \b os_messageQ_cb is implementation specific in every CMSIS-RTOS. +typedef struct os_messageQ_cb *osMessageQId; + +/// Mail ID identifies the mail queue (pointer to a mail queue control block). +/// \note CAN BE CHANGED: \b os_mailQ_cb is implementation specific in every CMSIS-RTOS. +typedef struct os_mailQ_cb *osMailQId; + + +/// Thread Definition structure contains startup information of a thread. +/// \note CAN BE CHANGED: \b os_thread_def is implementation specific in every CMSIS-RTOS. +typedef struct os_thread_def { + os_pthread pthread; ///< start address of thread function + osPriority tpriority; ///< initial thread priority + uint32_t instances; ///< maximum number of instances of that thread function + uint32_t stacksize; ///< stack size requirements in bytes; 0 is default stack size +} osThreadDef_t; + +/// Timer Definition structure contains timer parameters. +/// \note CAN BE CHANGED: \b os_timer_def is implementation specific in every CMSIS-RTOS. +typedef struct os_timer_def { + os_ptimer ptimer; ///< start address of a timer function + void *timer; ///< pointer to internal data +} osTimerDef_t; + +/// Mutex Definition structure contains setup information for a mutex. +/// \note CAN BE CHANGED: \b os_mutex_def is implementation specific in every CMSIS-RTOS. +typedef struct os_mutex_def { + void *mutex; ///< pointer to internal data +} osMutexDef_t; + +/// Semaphore Definition structure contains setup information for a semaphore. +/// \note CAN BE CHANGED: \b os_semaphore_def is implementation specific in every CMSIS-RTOS. +typedef struct os_semaphore_def { + void *semaphore; ///< pointer to internal data +} osSemaphoreDef_t; + +/// Definition structure for memory block allocation. +/// \note CAN BE CHANGED: \b os_pool_def is implementation specific in every CMSIS-RTOS. +typedef struct os_pool_def { + uint32_t pool_sz; ///< number of items (elements) in the pool + uint32_t item_sz; ///< size of an item + void *pool; ///< pointer to memory for pool +} osPoolDef_t; + +/// Definition structure for message queue. +/// \note CAN BE CHANGED: \b os_messageQ_def is implementation specific in every CMSIS-RTOS. +typedef struct os_messageQ_def { + uint32_t queue_sz; ///< number of elements in the queue + void *pool; ///< memory array for messages +} osMessageQDef_t; + +/// Definition structure for mail queue. +/// \note CAN BE CHANGED: \b os_mailQ_def is implementation specific in every CMSIS-RTOS. +typedef struct os_mailQ_def { + uint32_t queue_sz; ///< number of elements in the queue + uint32_t item_sz; ///< size of an item + void *pool; ///< memory array for mail +} osMailQDef_t; + +/// Event structure contains detailed information about an event. +/// \note MUST REMAIN UNCHANGED: \b os_event shall be consistent in every CMSIS-RTOS. +/// However the struct may be extended at the end. +typedef struct { + osStatus status; ///< status code: event or error information + union { + uint32_t v; ///< message as 32-bit value + void *p; ///< message or mail as void pointer + int32_t signals; ///< signal flags + } value; ///< event value + union { + osMailQId mail_id; ///< mail id obtained by \ref osMailCreate + osMessageQId message_id; ///< message id obtained by \ref osMessageCreate + } def; ///< event definition +} osEvent; + + +// ==== Kernel Control Functions ==== + +/// Initialize the RTOS Kernel for creating objects. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osKernelInitialize shall be consistent in every CMSIS-RTOS. +osStatus osKernelInitialize (void); + +/// Start the RTOS Kernel. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osKernelStart shall be consistent in every CMSIS-RTOS. +osStatus osKernelStart (void); + +/// Check if the RTOS kernel is already started. +/// \note MUST REMAIN UNCHANGED: \b osKernelRunning shall be consistent in every CMSIS-RTOS. +/// \return 0 RTOS is not started, 1 RTOS is started. +int32_t osKernelRunning(void); + + +// ==== Thread Management ==== + +/// Create a Thread Definition with function, priority, and stack requirements. +/// \param name name of the thread function. +/// \param priority initial priority of the thread function. +/// \param instances number of possible thread instances. +/// \param stacksz stack size (in bytes) requirements for the thread function. +/// \note CAN BE CHANGED: The parameters to \b osThreadDef shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#if defined (osObjectsExternal) // object is external +#define osThreadDef(name, priority, instances, stacksz) \ +extern const osThreadDef_t os_thread_def_##name +#else // define the object +#if defined (__MBED_CMSIS_RTOS_CA9) +#define osThreadDef(name, priority, stacksz) \ +const osThreadDef_t os_thread_def_##name = \ +{ (name), (priority), 1, (stacksz) } +#else +#define osThreadDef(name, priority, instances, stacksz) \ +const osThreadDef_t os_thread_def_##name = \ +{ (name), (priority), (instances), (stacksz) } +#endif +#endif + +/// Access a Thread definition. +/// \param name name of the thread definition object. +/// \note CAN BE CHANGED: The parameter to \b osThread shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#define osThread(name) \ +&os_thread_def_##name + +/// Create a thread and add it to Active Threads and set it to state READY. +/// \param[in] thread_def thread definition referenced with \ref osThread. +/// \param[in] argument pointer that is passed to the thread function as start argument. +/// \return thread ID for reference by other functions or NULL in case of error. +/// \note MUST REMAIN UNCHANGED: \b osThreadCreate shall be consistent in every CMSIS-RTOS. +osThreadId osThreadCreate (const osThreadDef_t *thread_def, void *argument); + +/// Return the thread ID of the current running thread. +/// \return thread ID for reference by other functions or NULL in case of error. +/// \note MUST REMAIN UNCHANGED: \b osThreadGetId shall be consistent in every CMSIS-RTOS. +osThreadId osThreadGetId (void); + +/// Terminate execution of a thread and remove it from Active Threads. +/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osThreadTerminate shall be consistent in every CMSIS-RTOS. +osStatus osThreadTerminate (osThreadId thread_id); + +/// Pass control to next thread that is in state \b READY. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osThreadYield shall be consistent in every CMSIS-RTOS. +osStatus osThreadYield (void); + +/// Change priority of an active thread. +/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId. +/// \param[in] priority new priority value for the thread function. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osThreadSetPriority shall be consistent in every CMSIS-RTOS. +osStatus osThreadSetPriority (osThreadId thread_id, osPriority priority); + +/// Get current priority of an active thread. +/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId. +/// \return current priority value of the thread function. +/// \note MUST REMAIN UNCHANGED: \b osThreadGetPriority shall be consistent in every CMSIS-RTOS. +osPriority osThreadGetPriority (osThreadId thread_id); + +#ifdef __MBED_CMSIS_RTOS_CA9 +/// Get current thread state. +uint8_t osThreadGetState (osThreadId thread_id); +#endif + +// ==== Generic Wait Functions ==== + +/// Wait for Timeout (Time Delay). +/// \param[in] millisec time delay value +/// \return status code that indicates the execution status of the function. +osStatus osDelay (uint32_t millisec); + +#if (defined (osFeature_Wait) && (osFeature_Wait != 0)) // Generic Wait available + +/// Wait for Signal, Message, Mail, or Timeout. +/// \param[in] millisec timeout value or 0 in case of no time-out +/// \return event that contains signal, message, or mail information or error code. +/// \note MUST REMAIN UNCHANGED: \b osWait shall be consistent in every CMSIS-RTOS. +os_InRegs osEvent osWait (uint32_t millisec); + +#endif // Generic Wait available + + +// ==== Timer Management Functions ==== +/// Define a Timer object. +/// \param name name of the timer object. +/// \param function name of the timer call back function. +/// \note CAN BE CHANGED: The parameter to \b osTimerDef shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#if defined (osObjectsExternal) // object is external +#define osTimerDef(name, function) \ +extern const osTimerDef_t os_timer_def_##name +#else // define the object +#define osTimerDef(name, function) \ +uint32_t os_timer_cb_##name[5]; \ +const osTimerDef_t os_timer_def_##name = \ +{ (function), (os_timer_cb_##name) } +#endif + +/// Access a Timer definition. +/// \param name name of the timer object. +/// \note CAN BE CHANGED: The parameter to \b osTimer shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#define osTimer(name) \ +&os_timer_def_##name + +/// Create a timer. +/// \param[in] timer_def timer object referenced with \ref osTimer. +/// \param[in] type osTimerOnce for one-shot or osTimerPeriodic for periodic behavior. +/// \param[in] argument argument to the timer call back function. +/// \return timer ID for reference by other functions or NULL in case of error. +/// \note MUST REMAIN UNCHANGED: \b osTimerCreate shall be consistent in every CMSIS-RTOS. +osTimerId osTimerCreate (const osTimerDef_t *timer_def, os_timer_type type, void *argument); + +/// Start or restart a timer. +/// \param[in] timer_id timer ID obtained by \ref osTimerCreate. +/// \param[in] millisec time delay value of the timer. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osTimerStart shall be consistent in every CMSIS-RTOS. +osStatus osTimerStart (osTimerId timer_id, uint32_t millisec); + +/// Stop the timer. +/// \param[in] timer_id timer ID obtained by \ref osTimerCreate. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osTimerStop shall be consistent in every CMSIS-RTOS. +osStatus osTimerStop (osTimerId timer_id); + +/// Delete a timer that was created by \ref osTimerCreate. +/// \param[in] timer_id timer ID obtained by \ref osTimerCreate. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osTimerDelete shall be consistent in every CMSIS-RTOS. +osStatus osTimerDelete (osTimerId timer_id); + + +// ==== Signal Management ==== + +/// Set the specified Signal Flags of an active thread. +/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId. +/// \param[in] signals specifies the signal flags of the thread that should be set. +/// \return previous signal flags of the specified thread or 0x80000000 in case of incorrect parameters. +/// \note MUST REMAIN UNCHANGED: \b osSignalSet shall be consistent in every CMSIS-RTOS. +int32_t osSignalSet (osThreadId thread_id, int32_t signals); + +/// Clear the specified Signal Flags of an active thread. +/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId. +/// \param[in] signals specifies the signal flags of the thread that shall be cleared. +/// \return previous signal flags of the specified thread or 0x80000000 in case of incorrect parameters. +/// \note MUST REMAIN UNCHANGED: \b osSignalClear shall be consistent in every CMSIS-RTOS. +int32_t osSignalClear (osThreadId thread_id, int32_t signals); + +/// Get Signal Flags status of an active thread. +/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId. +/// \return previous signal flags of the specified thread or 0x80000000 in case of incorrect parameters. +/// \note MUST REMAIN UNCHANGED: \b osSignalGet shall be consistent in every CMSIS-RTOS. +int32_t osSignalGet (osThreadId thread_id); + +/// Wait for one or more Signal Flags to become signaled for the current \b RUNNING thread. +/// \param[in] signals wait until all specified signal flags set or 0 for any single signal flag. +/// \param[in] millisec timeout value or 0 in case of no time-out. +/// \return event flag information or error code. +/// \note MUST REMAIN UNCHANGED: \b osSignalWait shall be consistent in every CMSIS-RTOS. +os_InRegs osEvent osSignalWait (int32_t signals, uint32_t millisec); + + +// ==== Mutex Management ==== + +/// Define a Mutex. +/// \param name name of the mutex object. +/// \note CAN BE CHANGED: The parameter to \b osMutexDef shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#if defined (osObjectsExternal) // object is external +#define osMutexDef(name) \ +extern const osMutexDef_t os_mutex_def_##name +#else // define the object +#define osMutexDef(name) \ +uint32_t os_mutex_cb_##name[3]; \ +const osMutexDef_t os_mutex_def_##name = { (os_mutex_cb_##name) } +#endif + +/// Access a Mutex definition. +/// \param name name of the mutex object. +/// \note CAN BE CHANGED: The parameter to \b osMutex shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#define osMutex(name) \ +&os_mutex_def_##name + +/// Create and Initialize a Mutex object. +/// \param[in] mutex_def mutex definition referenced with \ref osMutex. +/// \return mutex ID for reference by other functions or NULL in case of error. +/// \note MUST REMAIN UNCHANGED: \b osMutexCreate shall be consistent in every CMSIS-RTOS. +osMutexId osMutexCreate (const osMutexDef_t *mutex_def); + +/// Wait until a Mutex becomes available. +/// \param[in] mutex_id mutex ID obtained by \ref osMutexCreate. +/// \param[in] millisec timeout value or 0 in case of no time-out. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osMutexWait shall be consistent in every CMSIS-RTOS. +osStatus osMutexWait (osMutexId mutex_id, uint32_t millisec); + +/// Release a Mutex that was obtained by \ref osMutexWait. +/// \param[in] mutex_id mutex ID obtained by \ref osMutexCreate. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osMutexRelease shall be consistent in every CMSIS-RTOS. +osStatus osMutexRelease (osMutexId mutex_id); + +/// Delete a Mutex that was created by \ref osMutexCreate. +/// \param[in] mutex_id mutex ID obtained by \ref osMutexCreate. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osMutexDelete shall be consistent in every CMSIS-RTOS. +osStatus osMutexDelete (osMutexId mutex_id); + + +// ==== Semaphore Management Functions ==== + +#if (defined (osFeature_Semaphore) && (osFeature_Semaphore != 0)) // Semaphore available + +/// Define a Semaphore object. +/// \param name name of the semaphore object. +/// \note CAN BE CHANGED: The parameter to \b osSemaphoreDef shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#if defined (osObjectsExternal) // object is external +#define osSemaphoreDef(name) \ +extern const osSemaphoreDef_t os_semaphore_def_##name +#else // define the object +#define osSemaphoreDef(name) \ +uint32_t os_semaphore_cb_##name[2]; \ +const osSemaphoreDef_t os_semaphore_def_##name = { (os_semaphore_cb_##name) } +#endif + +/// Access a Semaphore definition. +/// \param name name of the semaphore object. +/// \note CAN BE CHANGED: The parameter to \b osSemaphore shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#define osSemaphore(name) \ +&os_semaphore_def_##name + +/// Create and Initialize a Semaphore object used for managing resources. +/// \param[in] semaphore_def semaphore definition referenced with \ref osSemaphore. +/// \param[in] count number of available resources. +/// \return semaphore ID for reference by other functions or NULL in case of error. +/// \note MUST REMAIN UNCHANGED: \b osSemaphoreCreate shall be consistent in every CMSIS-RTOS. +osSemaphoreId osSemaphoreCreate (const osSemaphoreDef_t *semaphore_def, int32_t count); + +/// Wait until a Semaphore token becomes available. +/// \param[in] semaphore_id semaphore object referenced with \ref osSemaphoreCreate. +/// \param[in] millisec timeout value or 0 in case of no time-out. +/// \return number of available tokens, or -1 in case of incorrect parameters. +/// \note MUST REMAIN UNCHANGED: \b osSemaphoreWait shall be consistent in every CMSIS-RTOS. +int32_t osSemaphoreWait (osSemaphoreId semaphore_id, uint32_t millisec); + +/// Release a Semaphore token. +/// \param[in] semaphore_id semaphore object referenced with \ref osSemaphoreCreate. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osSemaphoreRelease shall be consistent in every CMSIS-RTOS. +osStatus osSemaphoreRelease (osSemaphoreId semaphore_id); + +/// Delete a Semaphore that was created by \ref osSemaphoreCreate. +/// \param[in] semaphore_id semaphore object referenced with \ref osSemaphoreCreate. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osSemaphoreDelete shall be consistent in every CMSIS-RTOS. +osStatus osSemaphoreDelete (osSemaphoreId semaphore_id); + +#endif // Semaphore available + + +// ==== Memory Pool Management Functions ==== + +#if (defined (osFeature_Pool) && (osFeature_Pool != 0)) // Memory Pool Management available + +/// \brief Define a Memory Pool. +/// \param name name of the memory pool. +/// \param no maximum number of blocks (objects) in the memory pool. +/// \param type data type of a single block (object). +/// \note CAN BE CHANGED: The parameter to \b osPoolDef shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#if defined (osObjectsExternal) // object is external +#define osPoolDef(name, no, type) \ +extern const osPoolDef_t os_pool_def_##name +#else // define the object +#define osPoolDef(name, no, type) \ +uint32_t os_pool_m_##name[3+((sizeof(type)+3)/4)*(no)]; \ +const osPoolDef_t os_pool_def_##name = \ +{ (no), sizeof(type), (os_pool_m_##name) } +#endif + +/// \brief Access a Memory Pool definition. +/// \param name name of the memory pool +/// \note CAN BE CHANGED: The parameter to \b osPool shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#define osPool(name) \ +&os_pool_def_##name + +/// Create and Initialize a memory pool. +/// \param[in] pool_def memory pool definition referenced with \ref osPool. +/// \return memory pool ID for reference by other functions or NULL in case of error. +/// \note MUST REMAIN UNCHANGED: \b osPoolCreate shall be consistent in every CMSIS-RTOS. +osPoolId osPoolCreate (const osPoolDef_t *pool_def); + +/// Allocate a memory block from a memory pool. +/// \param[in] pool_id memory pool ID obtain referenced with \ref osPoolCreate. +/// \return address of the allocated memory block or NULL in case of no memory available. +/// \note MUST REMAIN UNCHANGED: \b osPoolAlloc shall be consistent in every CMSIS-RTOS. +void *osPoolAlloc (osPoolId pool_id); + +/// Allocate a memory block from a memory pool and set memory block to zero. +/// \param[in] pool_id memory pool ID obtain referenced with \ref osPoolCreate. +/// \return address of the allocated memory block or NULL in case of no memory available. +/// \note MUST REMAIN UNCHANGED: \b osPoolCAlloc shall be consistent in every CMSIS-RTOS. +void *osPoolCAlloc (osPoolId pool_id); + +/// Return an allocated memory block back to a specific memory pool. +/// \param[in] pool_id memory pool ID obtain referenced with \ref osPoolCreate. +/// \param[in] block address of the allocated memory block that is returned to the memory pool. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osPoolFree shall be consistent in every CMSIS-RTOS. +osStatus osPoolFree (osPoolId pool_id, void *block); + +#endif // Memory Pool Management available + + +// ==== Message Queue Management Functions ==== + +#if (defined (osFeature_MessageQ) && (osFeature_MessageQ != 0)) // Message Queues available + +/// \brief Create a Message Queue Definition. +/// \param name name of the queue. +/// \param queue_sz maximum number of messages in the queue. +/// \param type data type of a single message element (for debugger). +/// \note CAN BE CHANGED: The parameter to \b osMessageQDef shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#if defined (osObjectsExternal) // object is external +#define osMessageQDef(name, queue_sz, type) \ +extern const osMessageQDef_t os_messageQ_def_##name +#else // define the object +#define osMessageQDef(name, queue_sz, type) \ +uint32_t os_messageQ_q_##name[4+(queue_sz)]; \ +const osMessageQDef_t os_messageQ_def_##name = \ +{ (queue_sz), (os_messageQ_q_##name) } +#endif + +/// \brief Access a Message Queue Definition. +/// \param name name of the queue +/// \note CAN BE CHANGED: The parameter to \b osMessageQ shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#define osMessageQ(name) \ +&os_messageQ_def_##name + +/// Create and Initialize a Message Queue. +/// \param[in] queue_def queue definition referenced with \ref osMessageQ. +/// \param[in] thread_id thread ID (obtained by \ref osThreadCreate or \ref osThreadGetId) or NULL. +/// \return message queue ID for reference by other functions or NULL in case of error. +/// \note MUST REMAIN UNCHANGED: \b osMessageCreate shall be consistent in every CMSIS-RTOS. +osMessageQId osMessageCreate (const osMessageQDef_t *queue_def, osThreadId thread_id); + +/// Put a Message to a Queue. +/// \param[in] queue_id message queue ID obtained with \ref osMessageCreate. +/// \param[in] info message information. +/// \param[in] millisec timeout value or 0 in case of no time-out. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osMessagePut shall be consistent in every CMSIS-RTOS. +osStatus osMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec); + +/// Get a Message or Wait for a Message from a Queue. +/// \param[in] queue_id message queue ID obtained with \ref osMessageCreate. +/// \param[in] millisec timeout value or 0 in case of no time-out. +/// \return event information that includes status code. +/// \note MUST REMAIN UNCHANGED: \b osMessageGet shall be consistent in every CMSIS-RTOS. +os_InRegs osEvent osMessageGet (osMessageQId queue_id, uint32_t millisec); + +#endif // Message Queues available + + +// ==== Mail Queue Management Functions ==== + +#if (defined (osFeature_MailQ) && (osFeature_MailQ != 0)) // Mail Queues available + +/// \brief Create a Mail Queue Definition. +/// \param name name of the queue +/// \param queue_sz maximum number of messages in queue +/// \param type data type of a single message element +/// \note CAN BE CHANGED: The parameter to \b osMailQDef shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#if defined (osObjectsExternal) // object is external +#define osMailQDef(name, queue_sz, type) \ +extern const osMailQDef_t os_mailQ_def_##name +#else // define the object +#define osMailQDef(name, queue_sz, type) \ +uint32_t os_mailQ_q_##name[4+(queue_sz)]; \ +uint32_t os_mailQ_m_##name[3+((sizeof(type)+3)/4)*(queue_sz)]; \ +void * os_mailQ_p_##name[2] = { (os_mailQ_q_##name), os_mailQ_m_##name }; \ +const osMailQDef_t os_mailQ_def_##name = \ +{ (queue_sz), sizeof(type), (os_mailQ_p_##name) } +#endif + +/// \brief Access a Mail Queue Definition. +/// \param name name of the queue +/// \note CAN BE CHANGED: The parameter to \b osMailQ shall be consistent but the +/// macro body is implementation specific in every CMSIS-RTOS. +#define osMailQ(name) \ +&os_mailQ_def_##name + +/// Create and Initialize mail queue. +/// \param[in] queue_def reference to the mail queue definition obtain with \ref osMailQ +/// \param[in] thread_id thread ID (obtained by \ref osThreadCreate or \ref osThreadGetId) or NULL. +/// \return mail queue ID for reference by other functions or NULL in case of error. +/// \note MUST REMAIN UNCHANGED: \b osMailCreate shall be consistent in every CMSIS-RTOS. +osMailQId osMailCreate (const osMailQDef_t *queue_def, osThreadId thread_id); + +/// Allocate a memory block from a mail. +/// \param[in] queue_id mail queue ID obtained with \ref osMailCreate. +/// \param[in] millisec timeout value or 0 in case of no time-out +/// \return pointer to memory block that can be filled with mail or NULL in case of error. +/// \note MUST REMAIN UNCHANGED: \b osMailAlloc shall be consistent in every CMSIS-RTOS. +void *osMailAlloc (osMailQId queue_id, uint32_t millisec); + +/// Allocate a memory block from a mail and set memory block to zero. +/// \param[in] queue_id mail queue ID obtained with \ref osMailCreate. +/// \param[in] millisec timeout value or 0 in case of no time-out +/// \return pointer to memory block that can be filled with mail or NULL in case of error. +/// \note MUST REMAIN UNCHANGED: \b osMailCAlloc shall be consistent in every CMSIS-RTOS. +void *osMailCAlloc (osMailQId queue_id, uint32_t millisec); + +/// Put a mail to a queue. +/// \param[in] queue_id mail queue ID obtained with \ref osMailCreate. +/// \param[in] mail memory block previously allocated with \ref osMailAlloc or \ref osMailCAlloc. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osMailPut shall be consistent in every CMSIS-RTOS. +osStatus osMailPut (osMailQId queue_id, void *mail); + +/// Get a mail from a queue. +/// \param[in] queue_id mail queue ID obtained with \ref osMailCreate. +/// \param[in] millisec timeout value or 0 in case of no time-out +/// \return event that contains mail information or error code. +/// \note MUST REMAIN UNCHANGED: \b osMailGet shall be consistent in every CMSIS-RTOS. +os_InRegs osEvent osMailGet (osMailQId queue_id, uint32_t millisec); + +/// Free a memory block from a mail. +/// \param[in] queue_id mail queue ID obtained with \ref osMailCreate. +/// \param[in] mail pointer to the memory block that was obtained with \ref osMailGet. +/// \return status code that indicates the execution status of the function. +/// \note MUST REMAIN UNCHANGED: \b osMailFree shall be consistent in every CMSIS-RTOS. +osStatus osMailFree (osMailQId queue_id, void *mail); + +#endif // Mail Queues available + + +#ifdef __cplusplus +} +#endif + +#endif // _CMSIS_OS_H
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_CMSIS.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_CMSIS.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,2082 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: rt_CMSIS.c + * Purpose: CMSIS RTOS API + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#define __CMSIS_GENERIC + +#if defined (__CORTEX_M4) || defined (__CORTEX_M4F) + #include "core_cm4.h" +#elif defined (__CORTEX_M3) + #include "core_cm3.h" +#elif defined (__CORTEX_M0) + #include "core_cm0.h" +#elif defined (__CORTEX_A9) + #include "core_ca9.h" +#else + #error "Missing __CORTEX_xx definition" +#endif + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_System.h" +#include "rt_Task.h" +#include "rt_Event.h" +#include "rt_List.h" +#include "rt_Time.h" +#include "rt_Mutex.h" +#include "rt_Semaphore.h" +#include "rt_Mailbox.h" +#include "rt_MemBox.h" +#include "rt_Memory.h" +#include "rt_HAL_CM.h" + +#define os_thread_cb OS_TCB + +#include "cmsis_os.h" + +#if (osFeature_Signals != 16) +#error Invalid "osFeature_Signals" value! +#endif +#if (osFeature_Semaphore > 65535) +#error Invalid "osFeature_Semaphore" value! +#endif +#if (osFeature_Wait != 0) +#error osWait not supported! +#endif + + +// ==== Enumeration, structures, defines ==== + +// Service Calls defines + +#if defined (__CC_ARM) /* ARM Compiler */ + +#define __NO_RETURN __declspec(noreturn) + +#define osEvent_type osEvent +#define osEvent_ret_status ret +#define osEvent_ret_value ret +#define osEvent_ret_msg ret +#define osEvent_ret_mail ret + +#define osCallback_type osCallback +#define osCallback_ret ret + +#define SVC_0_1(f,t,...) \ +__svc_indirect(0) t _##f (t(*)()); \ + t f (void); \ +__attribute__((always_inline)) \ +static __inline t __##f (void) { \ + return _##f(f); \ +} + +#define SVC_1_1(f,t,t1,...) \ +__svc_indirect(0) t _##f (t(*)(t1),t1); \ + t f (t1 a1); \ +__attribute__((always_inline)) \ +static __inline t __##f (t1 a1) { \ + return _##f(f,a1); \ +} + +#define SVC_2_1(f,t,t1,t2,...) \ +__svc_indirect(0) t _##f (t(*)(t1,t2),t1,t2); \ + t f (t1 a1, t2 a2); \ +__attribute__((always_inline)) \ +static __inline t __##f (t1 a1, t2 a2) { \ + return _##f(f,a1,a2); \ +} + +#define SVC_3_1(f,t,t1,t2,t3,...) \ +__svc_indirect(0) t _##f (t(*)(t1,t2,t3),t1,t2,t3); \ + t f (t1 a1, t2 a2, t3 a3); \ +__attribute__((always_inline)) \ +static __inline t __##f (t1 a1, t2 a2, t3 a3) { \ + return _##f(f,a1,a2,a3); \ +} + +#define SVC_4_1(f,t,t1,t2,t3,t4,...) \ +__svc_indirect(0) t _##f (t(*)(t1,t2,t3,t4),t1,t2,t3,t4); \ + t f (t1 a1, t2 a2, t3 a3, t4 a4); \ +__attribute__((always_inline)) \ +static __inline t __##f (t1 a1, t2 a2, t3 a3, t4 a4) { \ + return _##f(f,a1,a2,a3,a4); \ +} + +#define SVC_1_2 SVC_1_1 +#define SVC_1_3 SVC_1_1 +#define SVC_2_3 SVC_2_1 + +#elif defined (__GNUC__) /* GNU Compiler */ + +#define __NO_RETURN __attribute__((noreturn)) + +typedef uint32_t __attribute__((vector_size(8))) ret64; +typedef uint32_t __attribute__((vector_size(16))) ret128; + +#define RET_pointer __r0 +#define RET_int32_t __r0 +#define RET_uint32_t __r0 +#define RET_osStatus __r0 +#define RET_osPriority __r0 +#define RET_osEvent {(osStatus)__r0, {(uint32_t)__r1}, {(void *)__r2}} +#define RET_osCallback {(void *)__r0, (void *)__r1} + +#if defined (__ARM_PCS_VFP) + +#define osEvent_type void +#define osEvent_ret_status { __asm ("MOV r0, %0;" \ + : /* no outputs */ \ + : "r"(ret.status) \ + : "r0" \ + ); \ + } +#define osEvent_ret_value { __asm ("MOV r1, %0;" \ + "MOV r0, %1;" \ + : /* no outputs */ \ + : "r"(ret.value.v), \ + "r"(ret.status) \ + : "r0", "r1" \ + ); \ + } +#define osEvent_ret_msg { __asm ("MOV r2, %0;" \ + "MOV r1, %1;" \ + "MOV r0, %2;" \ + : /* no outputs */ \ + : "r"(ret.def.message_id), \ + "r"(ret.value.v), \ + "r"(ret.status) \ + : "r0", "r1" , "r2" \ + ); \ + } + +#define osEvent_ret_mail { __asm ("MOV r2, %0;" \ + "MOV r1, %1;" \ + "MOV r0, %2;" \ + : /* no outputs */ \ + : "r"(ret.def.mail_id), \ + "r"(ret.value.v), \ + "r"(ret.status) \ + : "r0", "r1" , "r2" \ + ); \ + } + +#define osCallback_type void +#define osCallback_ret { __asm ("MOV r1, %0;" \ + "MOV r0, %1;" \ + : /* no outputs */ \ + : "r"(ret.arg), \ + "r"(ret.fp) \ + : "r0", "r1" \ + ); \ + } + +#else /* defined (__ARM_PCS_VFP) */ + +#define osEvent_type ret128 +#define osEvent_ret_status (ret128){ret.status} +#define osEvent_ret_value (ret128){ret.status, ret.value.v} +#define osEvent_ret_msg (ret128){ret.status, ret.value.v, (uint32_t)ret.def.message_id} +#define osEvent_ret_mail (ret128){ret.status, ret.value.v, (uint32_t)ret.def.mail_id} + +#define osCallback_type ret64 +#define osCallback_ret (ret64) {(uint32_t)ret.fp, (uint32_t)ret.arg} + +#endif /* defined (__ARM_PCS_VFP) */ + +#define SVC_ArgN(n) \ + register int __r##n __asm("r"#n); + +#define SVC_ArgR(n,t,a) \ + register t __r##n __asm("r"#n) = a; + +#define SVC_Arg0() \ + SVC_ArgN(0) \ + SVC_ArgN(1) \ + SVC_ArgN(2) \ + SVC_ArgN(3) + +#define SVC_Arg1(t1) \ + SVC_ArgR(0,t1,a1) \ + SVC_ArgN(1) \ + SVC_ArgN(2) \ + SVC_ArgN(3) + +#define SVC_Arg2(t1,t2) \ + SVC_ArgR(0,t1,a1) \ + SVC_ArgR(1,t2,a2) \ + SVC_ArgN(2) \ + SVC_ArgN(3) + +#define SVC_Arg3(t1,t2,t3) \ + SVC_ArgR(0,t1,a1) \ + SVC_ArgR(1,t2,a2) \ + SVC_ArgR(2,t3,a3) \ + SVC_ArgN(3) + +#define SVC_Arg4(t1,t2,t3,t4) \ + SVC_ArgR(0,t1,a1) \ + SVC_ArgR(1,t2,a2) \ + SVC_ArgR(2,t3,a3) \ + SVC_ArgR(3,t4,a4) + +#if (defined (__CORTEX_M0)) +#define SVC_Call(f) \ + __asm volatile \ + ( \ + "ldr r7,="#f"\n\t" \ + "mov r12,r7\n\t" \ + "svc 0" \ + : "=r" (__r0), "=r" (__r1), "=r" (__r2), "=r" (__r3) \ + : "r" (__r0), "r" (__r1), "r" (__r2), "r" (__r3) \ + : "r7", "r12", "lr", "cc" \ + ); +#else +#define SVC_Call(f) \ + __asm volatile \ + ( \ + "ldr r12,="#f"\n\t" \ + "svc 0" \ + : "=r" (__r0), "=r" (__r1), "=r" (__r2), "=r" (__r3) \ + : "r" (__r0), "r" (__r1), "r" (__r2), "r" (__r3) \ + : "r12", "lr", "cc" \ + ); +#endif + +#define SVC_0_1(f,t,rv) \ +__attribute__((always_inline)) \ +static inline t __##f (void) { \ + SVC_Arg0(); \ + SVC_Call(f); \ + return (t) rv; \ +} + +#define SVC_1_1(f,t,t1,rv) \ +__attribute__((always_inline)) \ +static inline t __##f (t1 a1) { \ + SVC_Arg1(t1); \ + SVC_Call(f); \ + return (t) rv; \ +} + +#define SVC_2_1(f,t,t1,t2,rv) \ +__attribute__((always_inline)) \ +static inline t __##f (t1 a1, t2 a2) { \ + SVC_Arg2(t1,t2); \ + SVC_Call(f); \ + return (t) rv; \ +} + +#define SVC_3_1(f,t,t1,t2,t3,rv) \ +__attribute__((always_inline)) \ +static inline t __##f (t1 a1, t2 a2, t3 a3) { \ + SVC_Arg3(t1,t2,t3); \ + SVC_Call(f); \ + return (t) rv; \ +} + +#define SVC_4_1(f,t,t1,t2,t3,t4,rv) \ +__attribute__((always_inline)) \ +static inline t __##f (t1 a1, t2 a2, t3 a3, t4 a4) { \ + SVC_Arg4(t1,t2,t3,t4); \ + SVC_Call(f); \ + return (t) rv; \ +} + +#define SVC_1_2 SVC_1_1 +#define SVC_1_3 SVC_1_1 +#define SVC_2_3 SVC_2_1 + +#elif defined (__ICCARM__) /* IAR Compiler */ + +#define __NO_RETURN __noreturn + +#define RET_osEvent "=r"(ret.status), "=r"(ret.value), "=r"(ret.def) +#define RET_osCallback "=r"(ret.fp), "=r"(ret.arg) + +#define osEvent_type osEvent +#define osEvent_ret_status ret +#define osEvent_ret_value ret +#define osEvent_ret_msg ret +#define osEvent_ret_mail ret + +#define osCallback_type uint64_t +#define osCallback_ret ((uint64_t)ret.fp | ((uint64_t)ret.arg)<<32) + +#define SVC_Setup(f) \ + __asm( \ + "mov r12,%0\n" \ + :: "r"(&f): "r12" \ + ); + +#define SVC_Ret3() \ + __asm( \ + "ldr r0,[sp,#0]\n" \ + "ldr r1,[sp,#4]\n" \ + "ldr r2,[sp,#8]\n" \ + ); + +#define SVC_0_1(f,t,...) \ +t f (void); \ +_Pragma("swi_number=0") __swi t _##f (void); \ +static inline t __##f (void) { \ + SVC_Setup(f); \ + return _##f(); \ +} + +#define SVC_1_1(f,t,t1,...) \ +t f (t1 a1); \ +_Pragma("swi_number=0") __swi t _##f (t1 a1); \ +static inline t __##f (t1 a1) { \ + SVC_Setup(f); \ + return _##f(a1); \ +} + +#define SVC_2_1(f,t,t1,t2,...) \ +t f (t1 a1, t2 a2); \ +_Pragma("swi_number=0") __swi t _##f (t1 a1, t2 a2); \ +static inline t __##f (t1 a1, t2 a2) { \ + SVC_Setup(f); \ + return _##f(a1,a2); \ +} + +#define SVC_3_1(f,t,t1,t2,t3,...) \ +t f (t1 a1, t2 a2, t3 a3); \ +_Pragma("swi_number=0") __swi t _##f (t1 a1, t2 a2, t3 a3); \ +static inline t __##f (t1 a1, t2 a2, t3 a3) { \ + SVC_Setup(f); \ + return _##f(a1,a2,a3); \ +} + +#define SVC_4_1(f,t,t1,t2,t3,t4,...) \ +t f (t1 a1, t2 a2, t3 a3, t4 a4); \ +_Pragma("swi_number=0") __swi t _##f (t1 a1, t2 a2, t3 a3, t4 a4); \ +static inline t __##f (t1 a1, t2 a2, t3 a3, t4 a4) { \ + SVC_Setup(f); \ + return _##f(a1,a2,a3,a4); \ +} + +#define SVC_1_2(f,t,t1,rr) \ +uint64_t f (t1 a1); \ +_Pragma("swi_number=0") __swi uint64_t _##f (t1 a1); \ +static inline t __##f (t1 a1) { \ + t ret; \ + SVC_Setup(f); \ + _##f(a1); \ + __asm("" : rr : :); \ + return ret; \ +} + +#define SVC_1_3(f,t,t1,rr) \ +t f (t1 a1); \ +void f##_ (t1 a1) { \ + f(a1); \ + SVC_Ret3(); \ +} \ +_Pragma("swi_number=0") __swi void _##f (t1 a1); \ +static inline t __##f (t1 a1) { \ + t ret; \ + SVC_Setup(f##_); \ + _##f(a1); \ + __asm("" : rr : :); \ + return ret; \ +} + +#define SVC_2_3(f,t,t1,t2,rr) \ +t f (t1 a1, t2 a2); \ +void f##_ (t1 a1, t2 a2) { \ + f(a1,a2); \ + SVC_Ret3(); \ +} \ +_Pragma("swi_number=0") __swi void _##f (t1 a1, t2 a2); \ +static inline t __##f (t1 a1, t2 a2) { \ + t ret; \ + SVC_Setup(f##_); \ + _##f(a1,a2); \ + __asm("" : rr : :); \ + return ret; \ +} + +#endif + + +// Callback structure +typedef struct { + void *fp; // Function pointer + void *arg; // Function argument +} osCallback; + + +// OS Section definitions +#ifdef OS_SECTIONS_LINK_INFO +extern const uint32_t os_section_id$$Base; +extern const uint32_t os_section_id$$Limit; +#endif + +// OS Stack Memory for Threads definitions +extern uint64_t os_stack_mem[]; +extern const uint32_t os_stack_sz; + +// OS Timers external resources +extern const osThreadDef_t os_thread_def_osTimerThread; +extern osThreadId osThreadId_osTimerThread; +extern const osMessageQDef_t os_messageQ_def_osTimerMessageQ; +extern osMessageQId osMessageQId_osTimerMessageQ; + +extern U32 IRQNestLevel; /* Indicates whether inside an ISR, and the depth of nesting. 0 = not in ISR. */ + + +// ==== Helper Functions ==== + +/// Convert timeout in millisec to system ticks +static uint32_t rt_ms2tick (uint32_t millisec) { + uint32_t tick; + + if (millisec == osWaitForever) return 0xFFFF; // Indefinite timeout + if (millisec > 4000000) return 0xFFFE; // Max ticks supported + + tick = ((1000 * millisec) + os_clockrate - 1) / os_clockrate; + if (tick > 0xFFFE) return 0xFFFE; + + return tick; +} + +/// Convert Thread ID to TCB pointer +static P_TCB rt_tid2ptcb (osThreadId thread_id) { + P_TCB ptcb; + + if (thread_id == NULL) return NULL; + + if ((uint32_t)thread_id & 3) return NULL; + +#ifdef OS_SECTIONS_LINK_INFO + if ((os_section_id$$Base != 0) && (os_section_id$$Limit != 0)) { + if (thread_id < (osThreadId)os_section_id$$Base) return NULL; + if (thread_id >= (osThreadId)os_section_id$$Limit) return NULL; + } +#endif + + ptcb = thread_id; + + if (ptcb->cb_type != TCB) return NULL; + + return ptcb; +} + +/// Convert ID pointer to Object pointer +static void *rt_id2obj (void *id) { + + if ((uint32_t)id & 3) return NULL; + +#ifdef OS_SECTIONS_LINK_INFO + if ((os_section_id$$Base != 0) && (os_section_id$$Limit != 0)) { + if (id < (void *)os_section_id$$Base) return NULL; + if (id >= (void *)os_section_id$$Limit) return NULL; + } +#endif + + return id; +} + +// === Helper functions for system call interface === + +static __inline char __get_mode(void) { + return (char)(__get_CPSR() & 0x1f); +} + +static __inline char __exceptional_mode(void) { + switch(__get_mode()) { + case MODE_USR: + case MODE_SYS: + return 0; + case MODE_SVC: + if (IRQNestLevel == 0) + return 0; /* handling a regular service call */ + else + return 1; /* handling an ISR in SVC mode */ + default: + return 1; + } +} + +// ==== Kernel Control ==== + +uint8_t os_initialized; // Kernel Initialized flag +uint8_t os_running; // Kernel Running flag + +// Kernel Control Service Calls declarations +SVC_0_1(svcKernelInitialize, osStatus, RET_osStatus) +SVC_0_1(svcKernelStart, osStatus, RET_osStatus) +SVC_0_1(svcKernelRunning, int32_t, RET_int32_t) + +static void sysThreadError (osStatus status); +osThreadId svcThreadCreate (const osThreadDef_t *thread_def, void *argument); +osMessageQId svcMessageCreate (const osMessageQDef_t *queue_def, osThreadId thread_id); + +// Kernel Control Service Calls + +/// Initialize the RTOS Kernel for creating objects +osStatus svcKernelInitialize (void) { + int ret; + + if (!os_initialized) { + + // Init Thread Stack Memory (must be 8-byte aligned) + if ((uint32_t)os_stack_mem & 7) return osErrorNoMemory; + ret = rt_init_mem(os_stack_mem, os_stack_sz); + if (ret != 0) return osErrorNoMemory; + + rt_sys_init(); // RTX System Initialization + } + + os_tsk.run->prio = 255; // Highest priority + + if (!os_initialized) { + // Create OS Timers resources (Message Queue & Thread) + osMessageQId_osTimerMessageQ = svcMessageCreate (&os_messageQ_def_osTimerMessageQ, NULL); + osThreadId_osTimerThread = svcThreadCreate(&os_thread_def_osTimerThread, NULL); + } + + sysThreadError(osOK); + + os_initialized = 1; + + return osOK; +} + +/// Start the RTOS Kernel +osStatus svcKernelStart (void) { + + if (os_running) return osOK; + + rt_tsk_prio(0, 0); // Lowest priority + __set_PSP(os_tsk.run->tsk_stack + 8*4); // New context + os_tsk.run = NULL; // Force context switch + + rt_sys_start(); + + os_running = 1; + + return osOK; +} + +/// Check if the RTOS kernel is already started +int32_t svcKernelRunning(void) { + return os_running; +} + +// Kernel Control Public API + +/// Initialize the RTOS Kernel for creating objects +osStatus osKernelInitialize (void) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + if (__get_mode() != MODE_USR) { + return svcKernelInitialize(); + } else { + return __svcKernelInitialize(); + } +} + +/// Start the RTOS Kernel +osStatus osKernelStart (void) { + char mode = __get_mode(); + + switch(mode) { + case MODE_USR: + if (os_flags & 1) return osErrorOS; // Privileged Thread mode requested from Unprivileged + break; + case MODE_SYS: + if (!(os_flags & 1)) { + __set_CPS_USR(); + } + break; + default: + return osErrorISR; // Not allowed in ISR + } + return __svcKernelStart(); +} + +/// Check if the RTOS kernel is already started +int32_t osKernelRunning(void) { + if(__get_mode() != MODE_USR) { + return os_running; + } else { + return __svcKernelRunning(); + } +} + + +// ==== Thread Management ==== + +/// Set Thread Error (for Create functions which return IDs) +static void sysThreadError (osStatus status) { + // To Do +} + +__NO_RETURN void osThreadExit (void); + +// Thread Service Calls declarations +SVC_2_1(svcThreadCreate, osThreadId, const osThreadDef_t *, void *, RET_pointer) +SVC_0_1(svcThreadGetId, osThreadId, RET_pointer) +SVC_1_1(svcThreadTerminate, osStatus, osThreadId, RET_osStatus) +SVC_0_1(svcThreadYield, osStatus, RET_osStatus) +SVC_2_1(svcThreadSetPriority, osStatus, osThreadId, osPriority, RET_osStatus) +SVC_1_1(svcThreadGetPriority, osPriority, osThreadId, RET_osPriority) + +// Thread Service Calls + +/// Create a thread and add it to Active Threads and set it to state READY +osThreadId svcThreadCreate (const osThreadDef_t *thread_def, void *argument) { + P_TCB ptcb; + OS_TID tsk; + void *stk; + + if ((thread_def == NULL) || + (thread_def->pthread == NULL) || + (thread_def->tpriority < osPriorityIdle) || + (thread_def->tpriority > osPriorityRealtime)) { + sysThreadError(osErrorParameter); + return NULL; + } + + if (thread_def->stacksize != 0) { // Custom stack size + stk = rt_alloc_mem( // Allocate stack + os_stack_mem, + thread_def->stacksize + ); + if (stk == NULL) { + sysThreadError(osErrorNoMemory); // Out of memory + return NULL; + } + } else { // Default stack size + stk = NULL; + } + + tsk = rt_tsk_create( // Create task + (FUNCP)thread_def->pthread, // Task function pointer + (thread_def->tpriority-osPriorityIdle+1) | // Task priority + (thread_def->stacksize << 8), // Task stack size in bytes + stk, // Pointer to task's stack + argument // Argument to the task + ); + + if (tsk == 0) { // Invalid task ID + if (stk != NULL) { + rt_free_mem(os_stack_mem, stk); // Free allocated stack + } + sysThreadError(osErrorNoMemory); // Create task failed (Out of memory) + return NULL; + } + + ptcb = (P_TCB)os_active_TCB[tsk - 1]; // TCB pointer + + *((uint32_t *)ptcb->tsk_stack + 13) = (uint32_t)osThreadExit; + + return ptcb; +} + +/// Return the thread ID of the current running thread +osThreadId svcThreadGetId (void) { + OS_TID tsk; + + tsk = rt_tsk_self(); + if (tsk == 0) return NULL; + return (P_TCB)os_active_TCB[tsk - 1]; +} + +/// Terminate execution of a thread and remove it from ActiveThreads +osStatus svcThreadTerminate (osThreadId thread_id) { + OS_RESULT res; + P_TCB ptcb; + void *stk; + + ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer + if (ptcb == NULL) return osErrorParameter; + + stk = ptcb->priv_stack ? ptcb->stack : NULL; // Private stack + + res = rt_tsk_delete(ptcb->task_id); // Delete task + + if (res == OS_R_NOK) return osErrorResource; // Delete task failed + + if (stk != NULL) { + rt_free_mem(os_stack_mem, stk); // Free private stack + } + + return osOK; +} + +/// Pass control to next thread that is in state READY +osStatus svcThreadYield (void) { + rt_tsk_pass(); // Pass control to next task + return osOK; +} + +/// Change priority of an active thread +osStatus svcThreadSetPriority (osThreadId thread_id, osPriority priority) { + OS_RESULT res; + P_TCB ptcb; + + ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer + if (ptcb == NULL) return osErrorParameter; + + if ((priority < osPriorityIdle) || (priority > osPriorityRealtime)) { + return osErrorValue; + } + + res = rt_tsk_prio( // Change task priority + ptcb->task_id, // Task ID + priority - osPriorityIdle + 1 // New task priority + ); + + if (res == OS_R_NOK) return osErrorResource; // Change task priority failed + + return osOK; +} + +/// Get current priority of an active thread +osPriority svcThreadGetPriority (osThreadId thread_id) { + P_TCB ptcb; + + ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer + if (ptcb == NULL) return osPriorityError; + + return (osPriority)(ptcb->prio - 1 + osPriorityIdle); +} + + +// Thread Public API + +/// Create a thread and add it to Active Threads and set it to state READY +osThreadId osThreadCreate (const osThreadDef_t *thread_def, void *argument) { + if (__exceptional_mode()) return NULL; // Not allowed in ISR + if ((__get_mode() != MODE_USR) && (os_running == 0)) { + // Privileged and not running + return svcThreadCreate(thread_def, argument); + } else { + return __svcThreadCreate(thread_def, argument); + } +} + +/// Return the thread ID of the current running thread +osThreadId osThreadGetId (void) { + if (__exceptional_mode()) return NULL; // Not allowed in ISR + return __svcThreadGetId(); +} + +/// Terminate execution of a thread and remove it from ActiveThreads +osStatus osThreadTerminate (osThreadId thread_id) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcThreadTerminate(thread_id); +} + +/// Pass control to next thread that is in state READY +osStatus osThreadYield (void) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcThreadYield(); +} + +/// Change priority of an active thread +osStatus osThreadSetPriority (osThreadId thread_id, osPriority priority) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcThreadSetPriority(thread_id, priority); +} + +/// Get current priority of an active thread +osPriority osThreadGetPriority (osThreadId thread_id) { + if (__exceptional_mode()) return osPriorityError;// Not allowed in ISR + return __svcThreadGetPriority(thread_id); +} + +/// INTERNAL - Not Public +/// Auto Terminate Thread on exit (used implicitly when thread exists) +__NO_RETURN void osThreadExit (void) { + __svcThreadTerminate(__svcThreadGetId()); + for (;;); // Should never come here +} + +#ifdef __MBED_CMSIS_RTOS_CA9 +/// Get current thread state +uint8_t osThreadGetState (osThreadId thread_id) { + P_TCB ptcb; + + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + + ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer + if (ptcb == NULL) return osErrorParameter; + + return ptcb->state; +} +#endif + +// ==== Generic Wait Functions ==== + +// Generic Wait Service Calls declarations +SVC_1_1(svcDelay, osStatus, uint32_t, RET_osStatus) +#if osFeature_Wait != 0 +SVC_1_3(svcWait, os_InRegs osEvent, uint32_t, RET_osEvent) +#endif + +// Generic Wait Service Calls + +/// Wait for Timeout (Time Delay) +osStatus svcDelay (uint32_t millisec) { + if (millisec == 0) return osOK; + rt_dly_wait(rt_ms2tick(millisec)); + return osEventTimeout; +} + +/// Wait for Signal, Message, Mail, or Timeout +#if osFeature_Wait != 0 +os_InRegs osEvent_type svcWait (uint32_t millisec) { + osEvent ret; + + if (millisec == 0) { + ret.status = osOK; +#if defined (__GNUC__) && defined (__ARM_PCS_VFP) + osEvent_ret_status; + return; +#else + return osEvent_ret_status; +#endif + } + + /* To Do: osEventSignal, osEventMessage, osEventMail */ + rt_dly_wait(rt_ms2tick(millisec)); + ret.status = osEventTimeout; + +#if defined (__GNUC__) && defined (__ARM_PCS_VFP) + osEvent_ret_status; + return; +#else + return osEvent_ret_status; +#endif +} +#endif + + +// Generic Wait API + +/// Wait for Timeout (Time Delay) +osStatus osDelay (uint32_t millisec) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcDelay(millisec); +} + +/// Wait for Signal, Message, Mail, or Timeout +os_InRegs osEvent osWait (uint32_t millisec) { + osEvent ret; + +#if osFeature_Wait == 0 + ret.status = osErrorOS; + return ret; +#else + if (__exceptional_mode()) { // Not allowed in ISR + ret.status = osErrorISR; + return ret; + } + return __svcWait(millisec); +#endif +} + + +// ==== Timer Management ==== + +// Timer definitions +#define osTimerInvalid 0 +#define osTimerStopped 1 +#define osTimerRunning 2 + +// Timer structures + +typedef struct os_timer_cb_ { // Timer Control Block + struct os_timer_cb_ *next; // Pointer to next active Timer + uint8_t state; // Timer State + uint8_t type; // Timer Type (Periodic/One-shot) + uint16_t reserved; // Reserved + uint16_t tcnt; // Timer Delay Count + uint16_t icnt; // Timer Initial Count + void *arg; // Timer Function Argument + const osTimerDef_t *timer; // Pointer to Timer definition +} os_timer_cb; + +// Timer variables +os_timer_cb *os_timer_head; // Pointer to first active Timer + + +// Timer Helper Functions + +// Insert Timer into the list sorted by time +static void rt_timer_insert (os_timer_cb *pt, uint32_t tcnt) { + os_timer_cb *p, *prev; + + prev = NULL; + p = os_timer_head; + while (p != NULL) { + if (tcnt < p->tcnt) break; + tcnt -= p->tcnt; + prev = p; + p = p->next; + } + pt->next = p; + pt->tcnt = (uint16_t)tcnt; + if (p != NULL) { + p->tcnt -= pt->tcnt; + } + if (prev != NULL) { + prev->next = pt; + } else { + os_timer_head = pt; + } +} + +// Remove Timer from the list +static int rt_timer_remove (os_timer_cb *pt) { + os_timer_cb *p, *prev; + + prev = NULL; + p = os_timer_head; + while (p != NULL) { + if (p == pt) break; + prev = p; + p = p->next; + } + if (p == NULL) return -1; + if (prev != NULL) { + prev->next = pt->next; + } else { + os_timer_head = pt->next; + } + if (pt->next != NULL) { + pt->next->tcnt += pt->tcnt; + } + + return 0; +} + + +// Timer Service Calls declarations +SVC_3_1(svcTimerCreate, osTimerId, const osTimerDef_t *, os_timer_type, void *, RET_pointer) +SVC_2_1(svcTimerStart, osStatus, osTimerId, uint32_t, RET_osStatus) +SVC_1_1(svcTimerStop, osStatus, osTimerId, RET_osStatus) +SVC_1_1(svcTimerDelete, osStatus, osTimerId, RET_osStatus) +SVC_1_2(svcTimerCall, os_InRegs osCallback, osTimerId, RET_osCallback) + +// Timer Management Service Calls + +/// Create timer +osTimerId svcTimerCreate (const osTimerDef_t *timer_def, os_timer_type type, void *argument) { + os_timer_cb *pt; + + if ((timer_def == NULL) || (timer_def->ptimer == NULL)) { + sysThreadError(osErrorParameter); + return NULL; + } + + pt = timer_def->timer; + if (pt == NULL) { + sysThreadError(osErrorParameter); + return NULL; + } + + if ((type != osTimerOnce) && (type != osTimerPeriodic)) { + sysThreadError(osErrorValue); + return NULL; + } + + if (osThreadId_osTimerThread == NULL) { + sysThreadError(osErrorResource); + return NULL; + } + + if (pt->state != osTimerInvalid){ + sysThreadError(osErrorResource); + return NULL; + } + + pt->state = osTimerStopped; + pt->type = (uint8_t)type; + pt->arg = argument; + pt->timer = timer_def; + + return (osTimerId)pt; +} + +/// Start or restart timer +osStatus svcTimerStart (osTimerId timer_id, uint32_t millisec) { + os_timer_cb *pt; + uint32_t tcnt; + + pt = rt_id2obj(timer_id); + if (pt == NULL) return osErrorParameter; + + tcnt = rt_ms2tick(millisec); + if (tcnt == 0) return osErrorValue; + + switch (pt->state) { + case osTimerRunning: + if (rt_timer_remove(pt) != 0) { + return osErrorResource; + } + break; + case osTimerStopped: + pt->state = osTimerRunning; + pt->icnt = (uint16_t)tcnt; + break; + default: + return osErrorResource; + } + + rt_timer_insert(pt, tcnt); + + return osOK; +} + +/// Stop timer +osStatus svcTimerStop (osTimerId timer_id) { + os_timer_cb *pt; + + pt = rt_id2obj(timer_id); + if (pt == NULL) return osErrorParameter; + + if (pt->state != osTimerRunning) return osErrorResource; + + pt->state = osTimerStopped; + + if (rt_timer_remove(pt) != 0) { + return osErrorResource; + } + + return osOK; +} + +/// Delete timer +osStatus svcTimerDelete (osTimerId timer_id) { + os_timer_cb *pt; + + pt = rt_id2obj(timer_id); + if (pt == NULL) return osErrorParameter; + + switch (pt->state) { + case osTimerRunning: + rt_timer_remove(pt); + break; + case osTimerStopped: + break; + default: + return osErrorResource; + } + + pt->state = osTimerInvalid; + + return osOK; +} + +/// Get timer callback parameters +os_InRegs osCallback_type svcTimerCall (osTimerId timer_id) { + os_timer_cb *pt; + osCallback ret; + + pt = rt_id2obj(timer_id); + if (pt == NULL) { + ret.fp = NULL; + ret.arg = NULL; +#if defined (__GNUC__) && defined (__ARM_PCS_VFP) + osCallback_ret; + return; +#else + return osCallback_ret; +#endif + } + + ret.fp = (void *)pt->timer->ptimer; + ret.arg = pt->arg; + +#if defined (__GNUC__) && defined (__ARM_PCS_VFP) + osCallback_ret; + return; +#else + return osCallback_ret; +#endif +} + +static __INLINE osStatus isrMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec); + +/// Timer Tick (called each SysTick) +void sysTimerTick (void) { + os_timer_cb *pt, *p; + + p = os_timer_head; + if (p == NULL) return; + + p->tcnt--; + while ((p != NULL) && (p->tcnt == 0)) { + pt = p; + p = p->next; + os_timer_head = p; + isrMessagePut(osMessageQId_osTimerMessageQ, (uint32_t)pt, 0); + if (pt->type == osTimerPeriodic) { + rt_timer_insert(pt, pt->icnt); + } else { + pt->state = osTimerStopped; + } + } +} + + +// Timer Management Public API + +/// Create timer +osTimerId osTimerCreate (const osTimerDef_t *timer_def, os_timer_type type, void *argument) { + if (__exceptional_mode()) return NULL; // Not allowed in ISR + if ((__get_mode() != MODE_USR) && (os_running == 0)) { + // Privileged and not running + return svcTimerCreate(timer_def, type, argument); + } else { + return __svcTimerCreate(timer_def, type, argument); + } +} + +/// Start or restart timer +osStatus osTimerStart (osTimerId timer_id, uint32_t millisec) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcTimerStart(timer_id, millisec); +} + +/// Stop timer +osStatus osTimerStop (osTimerId timer_id) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcTimerStop(timer_id); +} + +/// Delete timer +osStatus osTimerDelete (osTimerId timer_id) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcTimerDelete(timer_id); +} + +/// INTERNAL - Not Public +/// Get timer callback parameters (used by OS Timer Thread) +os_InRegs osCallback osTimerCall (osTimerId timer_id) { + return __svcTimerCall(timer_id); +} + + +// Timer Thread +__NO_RETURN void osTimerThread (void const *argument) { + osCallback cb; + osEvent evt; + + for (;;) { + evt = osMessageGet(osMessageQId_osTimerMessageQ, osWaitForever); + if (evt.status == osEventMessage) { + cb = osTimerCall(evt.value.p); + if (cb.fp != NULL) { + (*(os_ptimer)cb.fp)(cb.arg); + } + } + } +} + + +// ==== Signal Management ==== + +// Signal Service Calls declarations +SVC_2_1(svcSignalSet, int32_t, osThreadId, int32_t, RET_int32_t) +SVC_2_1(svcSignalClear, int32_t, osThreadId, int32_t, RET_int32_t) +SVC_1_1(svcSignalGet, int32_t, osThreadId, RET_int32_t) +SVC_2_3(svcSignalWait, os_InRegs osEvent, int32_t, uint32_t, RET_osEvent) + +// Signal Service Calls + +/// Set the specified Signal Flags of an active thread +int32_t svcSignalSet (osThreadId thread_id, int32_t signals) { + P_TCB ptcb; + int32_t sig; + + ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer + if (ptcb == NULL) return 0x80000000; + + if (signals & (0xFFFFFFFF << osFeature_Signals)) return 0x80000000; + + sig = ptcb->events; // Previous signal flags + + rt_evt_set(signals, ptcb->task_id); // Set event flags + + return sig; +} + +/// Clear the specified Signal Flags of an active thread +int32_t svcSignalClear (osThreadId thread_id, int32_t signals) { + P_TCB ptcb; + int32_t sig; + + ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer + if (ptcb == NULL) return 0x80000000; + + if (signals & (0xFFFFFFFF << osFeature_Signals)) return 0x80000000; + + sig = ptcb->events; // Previous signal flags + + rt_evt_clr(signals, ptcb->task_id); // Clear event flags + + return sig; +} + +/// Get Signal Flags status of an active thread +int32_t svcSignalGet (osThreadId thread_id) { + P_TCB ptcb; + + ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer + if (ptcb == NULL) return 0x80000000; + + return ptcb->events; // Return event flags +} + +/// Wait for one or more Signal Flags to become signaled for the current RUNNING thread +os_InRegs osEvent_type svcSignalWait (int32_t signals, uint32_t millisec) { + OS_RESULT res; + osEvent ret; + + if (signals & (0xFFFFFFFF << osFeature_Signals)) { + ret.status = osErrorValue; +#if defined (__GNUC__) && defined (__ARM_PCS_VFP) + osEvent_ret_status; + return; +#else + return osEvent_ret_status; +#endif + } + + if (signals != 0) { // Wait for all specified signals + res = rt_evt_wait(signals, rt_ms2tick(millisec), __TRUE); + } else { // Wait for any signal + res = rt_evt_wait(0xFFFF, rt_ms2tick(millisec), __FALSE); + } + + if (res == OS_R_EVT) { + ret.status = osEventSignal; + ret.value.signals = signals ? signals : os_tsk.run->waits; + } else { + ret.status = millisec ? osEventTimeout : osOK; + ret.value.signals = 0; + } + +#if defined (__GNUC__) && defined (__ARM_PCS_VFP) + osEvent_ret_value; + return; +#else + return osEvent_ret_value; +#endif +} + + +// Signal ISR Calls + +/// Set the specified Signal Flags of an active thread +static __INLINE int32_t isrSignalSet (osThreadId thread_id, int32_t signals) { + P_TCB ptcb; + int32_t sig; + + ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer + if (ptcb == NULL) return 0x80000000; + + if (signals & (0xFFFFFFFF << osFeature_Signals)) return 0x80000000; + + sig = ptcb->events; // Previous signal flags + + isr_evt_set(signals, ptcb->task_id); // Set event flags + + return sig; +} + + +// Signal Public API + +/// Set the specified Signal Flags of an active thread +int32_t osSignalSet (osThreadId thread_id, int32_t signals) { + if (__exceptional_mode()) { // in ISR + return isrSignalSet(thread_id, signals); + } else { // in Thread + return __svcSignalSet(thread_id, signals); + } +} + +/// Clear the specified Signal Flags of an active thread +int32_t osSignalClear (osThreadId thread_id, int32_t signals) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcSignalClear(thread_id, signals); +} + +/// Get Signal Flags status of an active thread +int32_t osSignalGet (osThreadId thread_id) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcSignalGet(thread_id); +} + +/// Wait for one or more Signal Flags to become signaled for the current RUNNING thread +os_InRegs osEvent osSignalWait (int32_t signals, uint32_t millisec) { + osEvent ret; + + if (__exceptional_mode()) { // Not allowed in ISR + ret.status = osErrorISR; + return ret; + } + return __svcSignalWait(signals, millisec); +} + + +// ==== Mutex Management ==== + +// Mutex Service Calls declarations +SVC_1_1(svcMutexCreate, osMutexId, const osMutexDef_t *, RET_pointer) +SVC_2_1(svcMutexWait, osStatus, osMutexId, uint32_t, RET_osStatus) +SVC_1_1(svcMutexRelease, osStatus, osMutexId, RET_osStatus) +SVC_1_1(svcMutexDelete, osStatus, osMutexId, RET_osStatus) + +// Mutex Service Calls + +/// Create and Initialize a Mutex object +osMutexId svcMutexCreate (const osMutexDef_t *mutex_def) { + OS_ID mut; + + if (mutex_def == NULL) { + sysThreadError(osErrorParameter); + return NULL; + } + + mut = mutex_def->mutex; + if (mut == NULL) { + sysThreadError(osErrorParameter); + return NULL; + } + + if (((P_MUCB)mut)->cb_type != 0) { + sysThreadError(osErrorParameter); + return NULL; + } + + rt_mut_init(mut); // Initialize Mutex + + return mut; +} + +/// Wait until a Mutex becomes available +osStatus svcMutexWait (osMutexId mutex_id, uint32_t millisec) { + OS_ID mut; + OS_RESULT res; + + mut = rt_id2obj(mutex_id); + if (mut == NULL) return osErrorParameter; + + if (((P_MUCB)mut)->cb_type != MUCB) return osErrorParameter; + + res = rt_mut_wait(mut, rt_ms2tick(millisec)); // Wait for Mutex + + if (res == OS_R_TMO) { + return (millisec ? osErrorTimeoutResource : osErrorResource); + } + + return osOK; +} + +/// Release a Mutex that was obtained with osMutexWait +osStatus svcMutexRelease (osMutexId mutex_id) { + OS_ID mut; + OS_RESULT res; + + mut = rt_id2obj(mutex_id); + if (mut == NULL) return osErrorParameter; + + if (((P_MUCB)mut)->cb_type != MUCB) return osErrorParameter; + + res = rt_mut_release(mut); // Release Mutex + + if (res == OS_R_NOK) return osErrorResource; // Thread not owner or Zero Counter + + return osOK; +} + +/// Delete a Mutex that was created by osMutexCreate +osStatus svcMutexDelete (osMutexId mutex_id) { + OS_ID mut; + + mut = rt_id2obj(mutex_id); + if (mut == NULL) return osErrorParameter; + + if (((P_MUCB)mut)->cb_type != MUCB) return osErrorParameter; + + rt_mut_delete(mut); // Release Mutex + + return osOK; +} + + +// Mutex Public API + +/// Create and Initialize a Mutex object +osMutexId osMutexCreate (const osMutexDef_t *mutex_def) { + if (__exceptional_mode()) return NULL; // Not allowed in ISR + if ((__get_mode() != MODE_USR) && (os_running == 0)) { + // Privileged and not running + return svcMutexCreate(mutex_def); + } else { + return __svcMutexCreate(mutex_def); + } +} + +/// Wait until a Mutex becomes available +osStatus osMutexWait (osMutexId mutex_id, uint32_t millisec) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcMutexWait(mutex_id, millisec); +} + +/// Release a Mutex that was obtained with osMutexWait +osStatus osMutexRelease (osMutexId mutex_id) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcMutexRelease(mutex_id); +} + +/// Delete a Mutex that was created by osMutexCreate +osStatus osMutexDelete (osMutexId mutex_id) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcMutexDelete(mutex_id); +} + + +// ==== Semaphore Management ==== + +// Semaphore Service Calls declarations +SVC_2_1(svcSemaphoreCreate, osSemaphoreId, const osSemaphoreDef_t *, int32_t, RET_pointer) +SVC_2_1(svcSemaphoreWait, int32_t, osSemaphoreId, uint32_t, RET_int32_t) +SVC_1_1(svcSemaphoreRelease, osStatus, osSemaphoreId, RET_osStatus) +SVC_1_1(svcSemaphoreDelete, osStatus, osSemaphoreId, RET_osStatus) + +// Semaphore Service Calls + +/// Create and Initialize a Semaphore object +osSemaphoreId svcSemaphoreCreate (const osSemaphoreDef_t *semaphore_def, int32_t count) { + OS_ID sem; + + if (semaphore_def == NULL) { + sysThreadError(osErrorParameter); + return NULL; + } + + sem = semaphore_def->semaphore; + if (sem == NULL) { + sysThreadError(osErrorParameter); + return NULL; + } + + if (((P_SCB)sem)->cb_type != 0) { + sysThreadError(osErrorParameter); + return NULL; + } + + if (count > osFeature_Semaphore) { + sysThreadError(osErrorValue); + return NULL; + } + + rt_sem_init(sem, count); // Initialize Semaphore + + return sem; +} + +/// Wait until a Semaphore becomes available +int32_t svcSemaphoreWait (osSemaphoreId semaphore_id, uint32_t millisec) { + OS_ID sem; + OS_RESULT res; + + sem = rt_id2obj(semaphore_id); + if (sem == NULL) return -1; + + if (((P_SCB)sem)->cb_type != SCB) return -1; + + res = rt_sem_wait(sem, rt_ms2tick(millisec)); // Wait for Semaphore + + if (res == OS_R_TMO) return 0; // Timeout + + return (((P_SCB)sem)->tokens + 1); +} + +/// Release a Semaphore +osStatus svcSemaphoreRelease (osSemaphoreId semaphore_id) { + OS_ID sem; + + sem = rt_id2obj(semaphore_id); + if (sem == NULL) return osErrorParameter; + + if (((P_SCB)sem)->cb_type != SCB) return osErrorParameter; + + if (((P_SCB)sem)->tokens == osFeature_Semaphore) return osErrorResource; + + rt_sem_send(sem); // Release Semaphore + + return osOK; +} + +/// Delete a Semaphore that was created by osSemaphoreCreate +osStatus svcSemaphoreDelete (osSemaphoreId semaphore_id) { + OS_ID sem; + + sem = rt_id2obj(semaphore_id); + if (sem == NULL) return osErrorParameter; + + if (((P_SCB)sem)->cb_type != SCB) return osErrorParameter; + + rt_sem_delete(sem); // Delete Semaphore + + return osOK; +} + + +// Semaphore ISR Calls + +/// Release a Semaphore +static __INLINE osStatus isrSemaphoreRelease (osSemaphoreId semaphore_id) { + OS_ID sem; + + sem = rt_id2obj(semaphore_id); + if (sem == NULL) return osErrorParameter; + + if (((P_SCB)sem)->cb_type != SCB) return osErrorParameter; + + if (((P_SCB)sem)->tokens == osFeature_Semaphore) return osErrorResource; + + isr_sem_send(sem); // Release Semaphore + + return osOK; +} + + +// Semaphore Public API + +/// Create and Initialize a Semaphore object +osSemaphoreId osSemaphoreCreate (const osSemaphoreDef_t *semaphore_def, int32_t count) { + if (__exceptional_mode()) return NULL; // Not allowed in ISR + if ((__get_mode() != MODE_USR) && (os_running == 0)) { + // Privileged and not running + return svcSemaphoreCreate(semaphore_def, count); + } else { + return __svcSemaphoreCreate(semaphore_def, count); + } +} + +/// Wait until a Semaphore becomes available +int32_t osSemaphoreWait (osSemaphoreId semaphore_id, uint32_t millisec) { + if (__exceptional_mode()) return -1; // Not allowed in ISR + return __svcSemaphoreWait(semaphore_id, millisec); +} + +/// Release a Semaphore +osStatus osSemaphoreRelease (osSemaphoreId semaphore_id) { + if (__exceptional_mode()) { // in ISR + return isrSemaphoreRelease(semaphore_id); + } else { // in Thread + return __svcSemaphoreRelease(semaphore_id); + } +} + +/// Delete a Semaphore that was created by osSemaphoreCreate +osStatus osSemaphoreDelete (osSemaphoreId semaphore_id) { + if (__exceptional_mode()) return osErrorISR; // Not allowed in ISR + return __svcSemaphoreDelete(semaphore_id); +} + + +// ==== Memory Management Functions ==== + +// Memory Management Helper Functions + +// Clear Memory Box (Zero init) +static void rt_clr_box (void *box_mem, void *box) { + uint32_t *p, n; + + if (box) { + p = box; + for (n = ((P_BM)box_mem)->blk_size; n; n -= 4) { + *p++ = 0; + } + } +} + +// Memory Management Service Calls declarations +SVC_1_1(svcPoolCreate, osPoolId, const osPoolDef_t *, RET_pointer) +SVC_2_1(sysPoolAlloc, void *, osPoolId, uint32_t, RET_pointer) +SVC_2_1(sysPoolFree, osStatus, osPoolId, void *, RET_osStatus) + +// Memory Management Service & ISR Calls + +/// Create and Initialize memory pool +osPoolId svcPoolCreate (const osPoolDef_t *pool_def) { + uint32_t blk_sz; + + if ((pool_def == NULL) || + (pool_def->pool_sz == 0) || + (pool_def->item_sz == 0) || + (pool_def->pool == NULL)) { + sysThreadError(osErrorParameter); + return NULL; + } + + blk_sz = (pool_def->item_sz + 3) & ~3; + + _init_box(pool_def->pool, sizeof(struct OS_BM) + pool_def->pool_sz * blk_sz, blk_sz); + + return pool_def->pool; +} + +/// Allocate a memory block from a memory pool +void *sysPoolAlloc (osPoolId pool_id, uint32_t clr) { + void *ptr; + + if (pool_id == NULL) return NULL; + + ptr = rt_alloc_box(pool_id); + if (clr) { + rt_clr_box(pool_id, ptr); + } + + return ptr; +} + +/// Return an allocated memory block back to a specific memory pool +osStatus sysPoolFree (osPoolId pool_id, void *block) { + int32_t res; + + if (pool_id == NULL) return osErrorParameter; + + res = rt_free_box(pool_id, block); + if (res != 0) return osErrorValue; + + return osOK; +} + + +// Memory Management Public API + +/// Create and Initialize memory pool +osPoolId osPoolCreate (const osPoolDef_t *pool_def) { + if (__exceptional_mode()) return NULL; // Not allowed in ISR + if ((__get_mode() != MODE_USR) && (os_running == 0)) { + // Privileged and not running + return svcPoolCreate(pool_def); + } else { + return __svcPoolCreate(pool_def); + } +} + +/// Allocate a memory block from a memory pool +void *osPoolAlloc (osPoolId pool_id) { + if (__get_mode() != MODE_USR) { // in ISR or Privileged + return sysPoolAlloc(pool_id, 0); + } else { // in Thread + return __sysPoolAlloc(pool_id, 0); + } +} + +/// Allocate a memory block from a memory pool and set memory block to zero +void *osPoolCAlloc (osPoolId pool_id) { + if (__get_mode() != MODE_USR) { // in ISR or Privileged + return sysPoolAlloc(pool_id, 1); + } else { // in Thread + return __sysPoolAlloc(pool_id, 1); + } +} + +/// Return an allocated memory block back to a specific memory pool +osStatus osPoolFree (osPoolId pool_id, void *block) { + if (__get_mode() != MODE_USR) { // in ISR or Privileged + return sysPoolFree(pool_id, block); + } else { // in Thread + return __sysPoolFree(pool_id, block); + } +} + + +// ==== Message Queue Management Functions ==== + +// Message Queue Management Service Calls declarations +SVC_2_1(svcMessageCreate, osMessageQId, const osMessageQDef_t *, osThreadId, RET_pointer) +SVC_3_1(svcMessagePut, osStatus, osMessageQId, uint32_t, uint32_t, RET_osStatus) +SVC_2_3(svcMessageGet, os_InRegs osEvent, osMessageQId, uint32_t, RET_osEvent) + +// Message Queue Service Calls + +/// Create and Initialize Message Queue +osMessageQId svcMessageCreate (const osMessageQDef_t *queue_def, osThreadId thread_id) { + + if ((queue_def == NULL) || + (queue_def->queue_sz == 0) || + (queue_def->pool == NULL)) { + sysThreadError(osErrorParameter); + return NULL; + } + + if (((P_MCB)queue_def->pool)->cb_type != 0) { + sysThreadError(osErrorParameter); + return NULL; + } + + rt_mbx_init(queue_def->pool, 4*(queue_def->queue_sz + 4)); + + return queue_def->pool; +} + +/// Put a Message to a Queue +osStatus svcMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec) { + OS_RESULT res; + + if (queue_id == NULL) return osErrorParameter; + + if (((P_MCB)queue_id)->cb_type != MCB) return osErrorParameter; + + res = rt_mbx_send(queue_id, (void *)info, rt_ms2tick(millisec)); + + if (res == OS_R_TMO) { + return (millisec ? osErrorTimeoutResource : osErrorResource); + } + + return osOK; +} + +/// Get a Message or Wait for a Message from a Queue +os_InRegs osEvent_type svcMessageGet (osMessageQId queue_id, uint32_t millisec) { + OS_RESULT res; + osEvent ret; + + if (queue_id == NULL) { + ret.status = osErrorParameter; +#if defined (__GNUC__) && defined (__ARM_PCS_VFP) + osEvent_ret_status; + return; +#else + return osEvent_ret_status; +#endif + } + + if (((P_MCB)queue_id)->cb_type != MCB) { + ret.status = osErrorParameter; +#if defined (__GNUC__) && defined (__ARM_PCS_VFP) + osEvent_ret_status; + return; +#else + return osEvent_ret_status; +#endif + } + + res = rt_mbx_wait(queue_id, &ret.value.p, rt_ms2tick(millisec)); + + if (res == OS_R_TMO) { + ret.status = millisec ? osEventTimeout : osOK; +#if defined (__GNUC__) && defined (__ARM_PCS_VFP) + osEvent_ret_value; + return; +#else + return osEvent_ret_value; +#endif + } + + ret.status = osEventMessage; + +#if defined (__GNUC__) && defined (__ARM_PCS_VFP) + osEvent_ret_value; + return; +#else + return osEvent_ret_value; +#endif +} + + +// Message Queue ISR Calls + +/// Put a Message to a Queue +static __INLINE osStatus isrMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec) { + + if ((queue_id == NULL) || (millisec != 0)) { + return osErrorParameter; + } + + if (((P_MCB)queue_id)->cb_type != MCB) return osErrorParameter; + + if (rt_mbx_check(queue_id) == 0) { // Check if Queue is full + return osErrorResource; + } + + isr_mbx_send(queue_id, (void *)info); + + return osOK; +} + +/// Get a Message or Wait for a Message from a Queue +static __INLINE os_InRegs osEvent isrMessageGet (osMessageQId queue_id, uint32_t millisec) { + OS_RESULT res; + osEvent ret; + + if ((queue_id == NULL) || (millisec != 0)) { + ret.status = osErrorParameter; + return ret; + } + + if (((P_MCB)queue_id)->cb_type != MCB) { + ret.status = osErrorParameter; + return ret; + } + + res = isr_mbx_receive(queue_id, &ret.value.p); + + if (res != OS_R_MBX) { + ret.status = osOK; + return ret; + } + + ret.status = osEventMessage; + + return ret; +} + + +// Message Queue Management Public API + +/// Create and Initialize Message Queue +osMessageQId osMessageCreate (const osMessageQDef_t *queue_def, osThreadId thread_id) { + if (__exceptional_mode()) return NULL; // Not allowed in ISR + if ((__get_mode() != MODE_USR) && (os_running == 0)) { + // Privileged and not running + return svcMessageCreate(queue_def, thread_id); + } else { + return __svcMessageCreate(queue_def, thread_id); + } +} + +/// Put a Message to a Queue +osStatus osMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec) { + if (__exceptional_mode()) { // in ISR + return isrMessagePut(queue_id, info, millisec); + } else { // in Thread + return __svcMessagePut(queue_id, info, millisec); + } +} + +/// Get a Message or Wait for a Message from a Queue +os_InRegs osEvent osMessageGet (osMessageQId queue_id, uint32_t millisec) { + if (__exceptional_mode()) { // in ISR + return isrMessageGet(queue_id, millisec); + } else { // in Thread + return __svcMessageGet(queue_id, millisec); + } +} + + +// ==== Mail Queue Management Functions ==== + +// Mail Queue Management Service Calls declarations +SVC_2_1(svcMailCreate, osMailQId, const osMailQDef_t *, osThreadId, RET_pointer) +SVC_4_1(sysMailAlloc, void *, osMailQId, uint32_t, uint32_t, uint32_t, RET_pointer) +SVC_3_1(sysMailFree, osStatus, osMailQId, void *, uint32_t, RET_osStatus) + +// Mail Queue Management Service & ISR Calls + +/// Create and Initialize mail queue +osMailQId svcMailCreate (const osMailQDef_t *queue_def, osThreadId thread_id) { + uint32_t blk_sz; + P_MCB pmcb; + void *pool; + + if ((queue_def == NULL) || + (queue_def->queue_sz == 0) || + (queue_def->item_sz == 0) || + (queue_def->pool == NULL)) { + sysThreadError(osErrorParameter); + return NULL; + } + + pmcb = *(((void **)queue_def->pool) + 0); + pool = *(((void **)queue_def->pool) + 1); + + if ((pool == NULL) || (pmcb == NULL) || (pmcb->cb_type != 0)) { + sysThreadError(osErrorParameter); + return NULL; + } + + blk_sz = (queue_def->item_sz + 3) & ~3; + + _init_box(pool, sizeof(struct OS_BM) + queue_def->queue_sz * blk_sz, blk_sz); + + rt_mbx_init(pmcb, 4*(queue_def->queue_sz + 4)); + + + return queue_def->pool; +} + +/// Allocate a memory block from a mail +void *sysMailAlloc (osMailQId queue_id, uint32_t millisec, uint32_t isr, uint32_t clr) { + P_MCB pmcb; + void *pool; + void *mem; + + if (queue_id == NULL) return NULL; + + pmcb = *(((void **)queue_id) + 0); + pool = *(((void **)queue_id) + 1); + + if ((pool == NULL) || (pmcb == NULL)) return NULL; + + if (isr && (millisec != 0)) return NULL; + + mem = rt_alloc_box(pool); + if (clr) { + rt_clr_box(pool, mem); + } + + if ((mem == NULL) && (millisec != 0)) { + // Put Task to sleep when Memory not available + if (pmcb->p_lnk != NULL) { + rt_put_prio((P_XCB)pmcb, os_tsk.run); + } else { + pmcb->p_lnk = os_tsk.run; + os_tsk.run->p_lnk = NULL; + os_tsk.run->p_rlnk = (P_TCB)pmcb; + // Task is waiting to allocate a message + pmcb->state = 3; + } + rt_block(rt_ms2tick(millisec), WAIT_MBX); + } + + return mem; +} + +/// Free a memory block from a mail +osStatus sysMailFree (osMailQId queue_id, void *mail, uint32_t isr) { + P_MCB pmcb; + P_TCB ptcb; + void *pool; + void *mem; + int32_t res; + + if (queue_id == NULL) return osErrorParameter; + + pmcb = *(((void **)queue_id) + 0); + pool = *(((void **)queue_id) + 1); + + if ((pmcb == NULL) || (pool == NULL)) return osErrorParameter; + + res = rt_free_box(pool, mail); + + if (res != 0) return osErrorValue; + + if (pmcb->state == 3) { + // Task is waiting to allocate a message + if (isr) { + rt_psq_enq (pmcb, (U32)pool); + rt_psh_req (); + } else { + mem = rt_alloc_box(pool); + if (mem != NULL) { + ptcb = rt_get_first((P_XCB)pmcb); + if (pmcb->p_lnk == NULL) { + pmcb->state = 0; + } + rt_ret_val(ptcb, (U32)mem); + rt_rmv_dly(ptcb); + rt_dispatch(ptcb); + } + } + } + + return osOK; +} + + +// Mail Queue Management Public API + +/// Create and Initialize mail queue +osMailQId osMailCreate (const osMailQDef_t *queue_def, osThreadId thread_id) { + if (__exceptional_mode()) return NULL; // Not allowed in ISR + if ((__get_mode() != MODE_USR) && (os_running == 0)) { + // Privileged and not running + return svcMailCreate(queue_def, thread_id); + } else { + return __svcMailCreate(queue_def, thread_id); + } +} + +/// Allocate a memory block from a mail +void *osMailAlloc (osMailQId queue_id, uint32_t millisec) { + if (__exceptional_mode()) { // in ISR + return sysMailAlloc(queue_id, millisec, 1, 0); + } else { // in Thread + return __sysMailAlloc(queue_id, millisec, 0, 0); + } +} + +/// Allocate a memory block from a mail and set memory block to zero +void *osMailCAlloc (osMailQId queue_id, uint32_t millisec) { + if (__exceptional_mode()) { // in ISR + return sysMailAlloc(queue_id, millisec, 1, 1); + } else { // in Thread + return __sysMailAlloc(queue_id, millisec, 0, 1); + } +} + +/// Free a memory block from a mail +osStatus osMailFree (osMailQId queue_id, void *mail) { + if (__exceptional_mode()) { // in ISR + return sysMailFree(queue_id, mail, 1); + } else { // in Thread + return __sysMailFree(queue_id, mail, 0); + } +} + +/// Put a mail to a queue +osStatus osMailPut (osMailQId queue_id, void *mail) { + if (queue_id == NULL) return osErrorParameter; + if (mail == NULL) return osErrorValue; + return osMessagePut(*((void **)queue_id), (uint32_t)mail, 0); +} + +/// Get a mail from a queue +os_InRegs osEvent osMailGet (osMailQId queue_id, uint32_t millisec) { + osEvent ret; + + if (queue_id == NULL) { + ret.status = osErrorParameter; + return ret; + } + + ret = osMessageGet(*((void **)queue_id), millisec); + if (ret.status == osEventMessage) ret.status = osEventMail; + + return ret; +}
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Event.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Event.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,194 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_EVENT.C + * Purpose: Implements waits and wake-ups for event flags + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_System.h" +#include "rt_Event.h" +#include "rt_List.h" +#include "rt_Task.h" +#ifdef __CORTEX_A9 +#include "rt_HAL_CA.h" +#else +#include "rt_HAL_CM.h" +#endif + + +/*---------------------------------------------------------------------------- + * Functions + *---------------------------------------------------------------------------*/ + + +/*--------------------------- rt_evt_wait -----------------------------------*/ + +OS_RESULT rt_evt_wait (U16 wait_flags, U16 timeout, BOOL and_wait) { + /* Wait for one or more event flags with optional time-out. */ + /* "wait_flags" identifies the flags to wait for. */ + /* "timeout" is the time-out limit in system ticks (0xffff if no time-out) */ + /* "and_wait" specifies the AND-ing of "wait_flags" as condition to be met */ + /* to complete the wait. (OR-ing if set to 0). */ + U32 block_state; + + if (and_wait) { + /* Check for AND-connected events */ + if ((os_tsk.run->events & wait_flags) == wait_flags) { + os_tsk.run->events &= ~wait_flags; + return (OS_R_EVT); + } + block_state = WAIT_AND; + } + else { + /* Check for OR-connected events */ + if (os_tsk.run->events & wait_flags) { + os_tsk.run->waits = os_tsk.run->events & wait_flags; + os_tsk.run->events &= ~wait_flags; + return (OS_R_EVT); + } + block_state = WAIT_OR; + } + /* Task has to wait */ + os_tsk.run->waits = wait_flags; + rt_block (timeout, (U8)block_state); + return (OS_R_TMO); +} + + +/*--------------------------- rt_evt_set ------------------------------------*/ + +void rt_evt_set (U16 event_flags, OS_TID task_id) { + /* Set one or more event flags of a selectable task. */ + P_TCB p_tcb; + + p_tcb = os_active_TCB[task_id-1]; + if (p_tcb == NULL) { + return; + } + p_tcb->events |= event_flags; + event_flags = p_tcb->waits; + /* If the task is not waiting for an event, it should not be put */ + /* to ready state. */ + if (p_tcb->state == WAIT_AND) { + /* Check for AND-connected events */ + if ((p_tcb->events & event_flags) == event_flags) { + goto wkup; + } + } + if (p_tcb->state == WAIT_OR) { + /* Check for OR-connected events */ + if (p_tcb->events & event_flags) { + p_tcb->waits &= p_tcb->events; +wkup: p_tcb->events &= ~event_flags; + rt_rmv_dly (p_tcb); + p_tcb->state = READY; +#ifdef __CMSIS_RTOS + rt_ret_val2(p_tcb, 0x08/*osEventSignal*/, p_tcb->waits); +#else + rt_ret_val (p_tcb, OS_R_EVT); +#endif + rt_dispatch (p_tcb); + } + } +} + + +/*--------------------------- rt_evt_clr ------------------------------------*/ + +void rt_evt_clr (U16 clear_flags, OS_TID task_id) { + /* Clear one or more event flags (identified by "clear_flags") of a */ + /* selectable task (identified by "task"). */ + P_TCB task = os_active_TCB[task_id-1]; + + if (task == NULL) { + return; + } + task->events &= ~clear_flags; +} + + +/*--------------------------- isr_evt_set -----------------------------------*/ + +void isr_evt_set (U16 event_flags, OS_TID task_id) { + /* Same function as "os_evt_set", but to be called by ISRs. */ + P_TCB p_tcb = os_active_TCB[task_id-1]; + + if (p_tcb == NULL) { + return; + } + rt_psq_enq (p_tcb, event_flags); + rt_psh_req (); +} + + +/*--------------------------- rt_evt_get ------------------------------------*/ + +U16 rt_evt_get (void) { + /* Get events of a running task after waiting for OR connected events. */ + return (os_tsk.run->waits); +} + + +/*--------------------------- rt_evt_psh ------------------------------------*/ + +void rt_evt_psh (P_TCB p_CB, U16 set_flags) { + /* Check if task has to be waken up */ + U16 event_flags; + + p_CB->events |= set_flags; + event_flags = p_CB->waits; + if (p_CB->state == WAIT_AND) { + /* Check for AND-connected events */ + if ((p_CB->events & event_flags) == event_flags) { + goto rdy; + } + } + if (p_CB->state == WAIT_OR) { + /* Check for OR-connected events */ + if (p_CB->events & event_flags) { + p_CB->waits &= p_CB->events; +rdy: p_CB->events &= ~event_flags; + rt_rmv_dly (p_CB); + p_CB->state = READY; +#ifdef __CMSIS_RTOS + rt_ret_val2(p_CB, 0x08/*osEventSignal*/, p_CB->waits); +#else + rt_ret_val (p_CB, OS_R_EVT); +#endif + rt_put_prio (&os_rdy, p_CB); + } + } +} + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Event.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Event.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,46 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_EVENT.H + * Purpose: Implements waits and wake-ups for event flags + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Functions */ +extern OS_RESULT rt_evt_wait (U16 wait_flags, U16 timeout, BOOL and_wait); +extern void rt_evt_set (U16 event_flags, OS_TID task_id); +extern void rt_evt_clr (U16 clear_flags, OS_TID task_id); +extern void isr_evt_set (U16 event_flags, OS_TID task_id); +extern U16 rt_evt_get (void); +extern void rt_evt_psh (P_TCB p_CB, U16 set_flags); + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_HAL_CA.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_HAL_CA.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,207 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_HAL_CM.H + * Purpose: Hardware Abstraction Layer for Cortex-A definitions + * Rev.: 21 Aug 2013 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2013 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Definitions */ +#define INIT_CPSR_SYS 0x4000001F +#define INIT_CPSR_USER 0x40000010 + +#define CPSR_T_BIT 0x20 +#define CPSR_I_BIT 0x80 +#define CPSR_F_BIT 0x40 + +#define MODE_USR 0x10 +#define MODE_FIQ 0x11 +#define MODE_IRQ 0x12 +#define MODE_SVC 0x13 +#define MODE_ABT 0x17 +#define MODE_UND 0x1B +#define MODE_SYS 0x1F + +#define MAGIC_WORD 0xE25A2EA5 + +#include "core_ca9.h" + +#if defined (__CC_ARM) /* ARM Compiler */ + +#if ((__TARGET_ARCH_7_M || __TARGET_ARCH_7E_M || __TARGET_ARCH_7_A) && !defined(NO_EXCLUSIVE_ACCESS)) + #define __USE_EXCLUSIVE_ACCESS +#else + #undef __USE_EXCLUSIVE_ACCESS +#endif + +#elif defined (__GNUC__) /* GNU Compiler */ + +#undef __USE_EXCLUSIVE_ACCESS + +#if defined (__VFP_FP__) && !defined(__SOFTFP__) +#define __TARGET_FPU_VFP 1 +#else +#define __TARGET_FPU_VFP 0 +#endif + +#define __inline inline +#define __weak __attribute__((weak)) + +#elif defined (__ICCARM__) /* IAR Compiler */ + +#error IAR Compiler support not implemented for Cortex-A + +#endif + +static U8 priority = 0xff; + +extern const U32 GICDistributor_BASE; +extern const U32 GICInterface_BASE; + +/* GIC registers - Distributor */ +#define GICD_ICDICER0 (*((volatile U32 *)(GICDistributor_BASE + 0x180))) /* - RW - Interrupt Clear-Enable Registers */ +#define GICD_ICDISER0 (*((volatile U32 *)(GICDistributor_BASE + 0x100))) /* - RW - Interrupt Set-Enable Registers */ +#define GICD_ICDIPR0 (*((volatile U32 *)(GICDistributor_BASE + 0x400))) /* - RW - Interrupt Priority Registers */ +#define GICD_ICDSGIR (*((volatile U32 *)(GICDistributor_BASE + 0xf00))) /* - RW - Interrupt Software Interrupt Register */ +#define GICD_ICDICERx(irq) *(volatile U32 *)(&GICD_ICDICER0 + irq/32) +#define GICD_ICDISERx(irq) *(volatile U32 *)(&GICD_ICDISER0 + irq/32) + +/* GIC register - CPU Interface */ +#define GICI_ICCPMR (*((volatile U32 *)(GICInterface_BASE + 0x004))) /* - RW - Interrupt Priority Mask Register */ + +#define SGI_PENDSV 0 /* SGI0 */ +#define SGI_PENDSV_BIT ((U32)(1 << (SGI_PENDSV & 0xf))) + +//Increase priority filter to prevent timer and PendSV interrupts signaling. Guarantees that interrupts will not be forwarded. +#define OS_LOCK() int irq_dis = __disable_irq();\ + priority = GICI_ICCPMR; \ + GICI_ICCPMR = 0xff; \ + GICI_ICCPMR = GICI_ICCPMR - 1; \ + __DSB();\ + if(!irq_dis) __enable_irq(); \ + +//Restore priority filter. Re-enable timer and PendSV signaling +#define OS_UNLOCK() __DSB(); \ + GICI_ICCPMR = priority; \ + +#define OS_PEND_IRQ() GICD_ICDSGIR = 0x0010000 | SGI_PENDSV +#define OS_PEND(fl,p) if(p) OS_PEND_IRQ(); +#define OS_UNPEND(fl) + +/* HW initialization needs to be done in os_tick_init (void) -RTX_Conf_CM.c- + * OS_X_INIT enables the IRQ n in the GIC */ +#define OS_X_INIT(n) volatile char *reg; \ + reg = (char *)(&GICD_ICDIPR0 + n / 4); \ + reg += n % 4; \ + *reg = (char)0xff; \ + *reg = *reg - 1; \ + GICD_ICDISERx(n) = (U32)(1 << n % 32); +#define OS_X_LOCK(n) OS_LOCK() +#define OS_X_UNLOCK(n) OS_UNLOCK() +#define OS_X_PEND_IRQ() OS_PEND_IRQ() +#define OS_X_PEND(fl,p) if(p) OS_X_PEND_IRQ(); +#define OS_X_UNPEND(fl) + + +/* Functions */ +#ifdef __USE_EXCLUSIVE_ACCESS + #define rt_inc(p) while(__strex((__ldrex(p)+1),p)) + #define rt_dec(p) while(__strex((__ldrex(p)-1),p)) +#else + #define rt_inc(p) { int irq_dis = __disable_irq();(*p)++;if(!irq_dis) __enable_irq(); } + #define rt_dec(p) { int irq_dis = __disable_irq();(*p)--;if(!irq_dis) __enable_irq(); } +#endif + +__inline static U32 rt_inc_qi (U32 size, U8 *count, U8 *first) { + U32 cnt,c2; +#ifdef __USE_EXCLUSIVE_ACCESS + do { + if ((cnt = __ldrex(count)) == size) { + __clrex(); + return (cnt); } + } while (__strex(cnt+1, count)); + do { + c2 = (cnt = __ldrex(first)) + 1; + if (c2 == size) c2 = 0; + } while (__strex(c2, first)); +#else + int irq_dis; + irq_dis = __disable_irq(); + if ((cnt = *count) < size) { + *count = cnt+1; + c2 = (cnt = *first) + 1; + if (c2 == size) c2 = 0; + *first = c2; + } + if(!irq_dis) __enable_irq (); +#endif + return (cnt); +} + +__inline static void rt_systick_init (void) { + /* Cortex-A doesn't have a Systick. User needs to provide an alternative timer using RTX_Conf_CM configuration */ + /* HW initialization needs to be done in os_tick_init (void) -RTX_Conf_CM.c- */ +} + +__inline static void rt_svc_init (void) { + /* Register pendSV - through SGI */ + volatile char *reg; + + reg = (char *)(&GICD_ICDIPR0 + SGI_PENDSV/4); + reg += SGI_PENDSV % 4; + /* Write 0xff to read priority level */ + *reg = (char)0xff; + /* Read priority level and set the lowest possible*/ + *reg = *reg - 1; + + GICD_ICDISERx(SGI_PENDSV) = (U32)SGI_PENDSV_BIT; +} + +extern void rt_set_PSP (U32 stack); +extern U32 rt_get_PSP (void); +extern void os_set_env (P_TCB p_TCB); +extern void *_alloc_box (void *box_mem); +extern int _free_box (void *box_mem, void *box); + +extern void rt_init_stack (P_TCB p_TCB, FUNCP task_body); +extern void rt_ret_val (P_TCB p_TCB, U32 v0); +extern void rt_ret_val2 (P_TCB p_TCB, U32 v0, U32 v1); + +extern void dbg_init (void); +extern void dbg_task_notify (P_TCB p_tcb, BOOL create); +extern void dbg_task_switch (U32 task_id); + +#define DBG_INIT() +#define DBG_TASK_NOTIFY(p_tcb,create) +#define DBG_TASK_SWITCH(task_id) + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_HAL_CM.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_HAL_CM.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,276 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_HAL_CM.H + * Purpose: Hardware Abstraction Layer for Cortex-M definitions + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Definitions */ +#define INITIAL_xPSR 0x01000000 +#define DEMCR_TRCENA 0x01000000 +#define ITM_ITMENA 0x00000001 +#define MAGIC_WORD 0xE25A2EA5 + +#if defined (__CC_ARM) /* ARM Compiler */ + +#if ((__TARGET_ARCH_7_M || __TARGET_ARCH_7E_M) && !NO_EXCLUSIVE_ACCESS) + #define __USE_EXCLUSIVE_ACCESS +#else + #undef __USE_EXCLUSIVE_ACCESS +#endif + +#elif defined (__GNUC__) /* GNU Compiler */ + +#undef __USE_EXCLUSIVE_ACCESS + +#if defined (__CORTEX_M0) +#define __TARGET_ARCH_6S_M 1 +#else +#define __TARGET_ARCH_6S_M 0 +#endif + +#if defined (__VFP_FP__) && !defined(__SOFTFP__) +#define __TARGET_FPU_VFP 1 +#else +#define __TARGET_FPU_VFP 0 +#endif + +#define __inline inline +#define __weak __attribute__((weak)) + +#ifndef __CMSIS_GENERIC + +__attribute__((always_inline)) static inline void __enable_irq(void) +{ + __asm volatile ("cpsie i"); +} + +__attribute__((always_inline)) static inline U32 __disable_irq(void) +{ + U32 result; + + __asm volatile ("mrs %0, primask" : "=r" (result)); + __asm volatile ("cpsid i"); + return(result & 1); +} + +#endif + +__attribute__(( always_inline)) static inline U8 __clz(U32 value) +{ + U8 result; + + __asm volatile ("clz %0, %1" : "=r" (result) : "r" (value)); + return(result); +} + +#elif defined (__ICCARM__) /* IAR Compiler */ + +#undef __USE_EXCLUSIVE_ACCESS + +#if (__CORE__ == __ARM6M__) +#define __TARGET_ARCH_6S_M 1 +#else +#define __TARGET_ARCH_6S_M 0 +#endif + +#if defined __ARMVFP__ +#define __TARGET_FPU_VFP 1 +#else +#define __TARGET_FPU_VFP 0 +#endif + +#define __inline inline + +#ifndef __CMSIS_GENERIC + +static inline void __enable_irq(void) +{ + __asm volatile ("cpsie i"); +} + +static inline U32 __disable_irq(void) +{ + U32 result; + + __asm volatile ("mrs %0, primask" : "=r" (result)); + __asm volatile ("cpsid i"); + return(result & 1); +} + +#endif + +static inline U8 __clz(U32 value) +{ + U8 result; + + __asm volatile ("clz %0, %1" : "=r" (result) : "r" (value)); + return(result); +} + +#endif + +/* NVIC registers */ +#define NVIC_ST_CTRL (*((volatile U32 *)0xE000E010)) +#define NVIC_ST_RELOAD (*((volatile U32 *)0xE000E014)) +#define NVIC_ST_CURRENT (*((volatile U32 *)0xE000E018)) +#define NVIC_ISER ((volatile U32 *)0xE000E100) +#define NVIC_ICER ((volatile U32 *)0xE000E180) +#if (__TARGET_ARCH_6S_M) +#define NVIC_IP ((volatile U32 *)0xE000E400) +#else +#define NVIC_IP ((volatile U8 *)0xE000E400) +#endif +#define NVIC_INT_CTRL (*((volatile U32 *)0xE000ED04)) +#define NVIC_AIR_CTRL (*((volatile U32 *)0xE000ED0C)) +#define NVIC_SYS_PRI2 (*((volatile U32 *)0xE000ED1C)) +#define NVIC_SYS_PRI3 (*((volatile U32 *)0xE000ED20)) + +#define OS_PEND_IRQ() NVIC_INT_CTRL = (1<<28) +#define OS_PENDING ((NVIC_INT_CTRL >> 26) & (1<<2 | 1)) +#define OS_UNPEND(fl) NVIC_INT_CTRL = (*fl = OS_PENDING) << 25 +#define OS_PEND(fl,p) NVIC_INT_CTRL = (fl | p<<2) << 26 +#define OS_LOCK() NVIC_ST_CTRL = 0x0005 +#define OS_UNLOCK() NVIC_ST_CTRL = 0x0007 + +#define OS_X_PENDING ((NVIC_INT_CTRL >> 28) & 1) +#define OS_X_UNPEND(fl) NVIC_INT_CTRL = (*fl = OS_X_PENDING) << 27 +#define OS_X_PEND(fl,p) NVIC_INT_CTRL = (fl | p) << 28 +#if (__TARGET_ARCH_6S_M) +#define OS_X_INIT(n) NVIC_IP[n>>2] |= 0xFF << (8*(n & 0x03)); \ + NVIC_ISER[n>>5] = 1 << (n & 0x1F) +#else +#define OS_X_INIT(n) NVIC_IP[n] = 0xFF; \ + NVIC_ISER[n>>5] = 1 << (n & 0x1F) +#endif +#define OS_X_LOCK(n) NVIC_ICER[n>>5] = 1 << (n & 0x1F) +#define OS_X_UNLOCK(n) NVIC_ISER[n>>5] = 1 << (n & 0x1F) + +/* Core Debug registers */ +#define DEMCR (*((volatile U32 *)0xE000EDFC)) + +/* ITM registers */ +#define ITM_CONTROL (*((volatile U32 *)0xE0000E80)) +#define ITM_ENABLE (*((volatile U32 *)0xE0000E00)) +#define ITM_PORT30_U32 (*((volatile U32 *)0xE0000078)) +#define ITM_PORT31_U32 (*((volatile U32 *)0xE000007C)) +#define ITM_PORT31_U16 (*((volatile U16 *)0xE000007C)) +#define ITM_PORT31_U8 (*((volatile U8 *)0xE000007C)) + +/* Variables */ +extern BIT dbg_msg; + +/* Functions */ +#ifdef __USE_EXCLUSIVE_ACCESS + #define rt_inc(p) while(__strex((__ldrex(p)+1),p)) + #define rt_dec(p) while(__strex((__ldrex(p)-1),p)) +#else + #define rt_inc(p) __disable_irq();(*p)++;__enable_irq(); + #define rt_dec(p) __disable_irq();(*p)--;__enable_irq(); +#endif + +__inline static U32 rt_inc_qi (U32 size, U8 *count, U8 *first) { + U32 cnt,c2; +#ifdef __USE_EXCLUSIVE_ACCESS + do { + if ((cnt = __ldrex(count)) == size) { + __clrex(); + return (cnt); } + } while (__strex(cnt+1, count)); + do { + c2 = (cnt = __ldrex(first)) + 1; + if (c2 == size) c2 = 0; + } while (__strex(c2, first)); +#else + __disable_irq(); + if ((cnt = *count) < size) { + *count = cnt+1; + c2 = (cnt = *first) + 1; + if (c2 == size) c2 = 0; + *first = c2; + } + __enable_irq (); +#endif + return (cnt); +} + +__inline static void rt_systick_init (void) { + NVIC_ST_RELOAD = os_trv; + NVIC_ST_CURRENT = 0; + NVIC_ST_CTRL = 0x0007; + NVIC_SYS_PRI3 |= 0xFF000000; +} + +__inline static void rt_svc_init (void) { +#if !(__TARGET_ARCH_6S_M) + int sh,prigroup; +#endif + NVIC_SYS_PRI3 |= 0x00FF0000; +#if (__TARGET_ARCH_6S_M) + NVIC_SYS_PRI2 |= (NVIC_SYS_PRI3<<(8+1)) & 0xFC000000; +#else + sh = 8 - __clz (~((NVIC_SYS_PRI3 << 8) & 0xFF000000)); + prigroup = ((NVIC_AIR_CTRL >> 8) & 0x07); + if (prigroup >= sh) { + sh = prigroup + 1; + } + NVIC_SYS_PRI2 = ((0xFEFFFFFF << sh) & 0xFF000000) | (NVIC_SYS_PRI2 & 0x00FFFFFF); +#endif +} + +extern void rt_set_PSP (U32 stack); +extern U32 rt_get_PSP (void); +extern void os_set_env (void); +extern void *_alloc_box (void *box_mem); +extern int _free_box (void *box_mem, void *box); + +extern void rt_init_stack (P_TCB p_TCB, FUNCP task_body); +extern void rt_ret_val (P_TCB p_TCB, U32 v0); +extern void rt_ret_val2 (P_TCB p_TCB, U32 v0, U32 v1); + +extern void dbg_init (void); +extern void dbg_task_notify (P_TCB p_tcb, BOOL create); +extern void dbg_task_switch (U32 task_id); + +#ifdef DBG_MSG +#define DBG_INIT() dbg_init() +#define DBG_TASK_NOTIFY(p_tcb,create) if (dbg_msg) dbg_task_notify(p_tcb,create) +#define DBG_TASK_SWITCH(task_id) if (dbg_msg && (os_tsk.new!=os_tsk.run)) \ + dbg_task_switch(task_id) +#else +#define DBG_INIT() +#define DBG_TASK_NOTIFY(p_tcb,create) +#define DBG_TASK_SWITCH(task_id) +#endif + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_List.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_List.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,324 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_LIST.C + * Purpose: Functions for the management of different lists + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_System.h" +#include "rt_List.h" +#include "rt_Task.h" +#include "rt_Time.h" +#ifdef __CORTEX_A9 +#include "rt_HAL_CA.h" +#else +#include "rt_HAL_CM.h" +#endif + +/*---------------------------------------------------------------------------- + * Global Variables + *---------------------------------------------------------------------------*/ + +/* List head of chained ready tasks */ +struct OS_XCB os_rdy; +/* List head of chained delay tasks */ +struct OS_XCB os_dly; + + +/*---------------------------------------------------------------------------- + * Functions + *---------------------------------------------------------------------------*/ + + +/*--------------------------- rt_put_prio -----------------------------------*/ + +void rt_put_prio (P_XCB p_CB, P_TCB p_task) { + /* Put task identified with "p_task" into list ordered by priority. */ + /* "p_CB" points to head of list; list has always an element at end with */ + /* a priority less than "p_task->prio". */ + P_TCB p_CB2; + U32 prio; + BOOL sem_mbx = __FALSE; + + if (p_CB->cb_type == SCB || p_CB->cb_type == MCB || p_CB->cb_type == MUCB) { + sem_mbx = __TRUE; + } + prio = p_task->prio; + p_CB2 = p_CB->p_lnk; + /* Search for an entry in the list */ + while (p_CB2 != NULL && prio <= p_CB2->prio) { + p_CB = (P_XCB)p_CB2; + p_CB2 = p_CB2->p_lnk; + } + /* Entry found, insert the task into the list */ + p_task->p_lnk = p_CB2; + p_CB->p_lnk = p_task; + if (sem_mbx) { + if (p_CB2 != NULL) { + p_CB2->p_rlnk = p_task; + } + p_task->p_rlnk = (P_TCB)p_CB; + } + else { + p_task->p_rlnk = NULL; + } +} + + +/*--------------------------- rt_get_first ----------------------------------*/ + +P_TCB rt_get_first (P_XCB p_CB) { + /* Get task at head of list: it is the task with highest priority. */ + /* "p_CB" points to head of list. */ + P_TCB p_first; + + p_first = p_CB->p_lnk; + p_CB->p_lnk = p_first->p_lnk; + if (p_CB->cb_type == SCB || p_CB->cb_type == MCB || p_CB->cb_type == MUCB) { + if (p_first->p_lnk != NULL) { + p_first->p_lnk->p_rlnk = (P_TCB)p_CB; + p_first->p_lnk = NULL; + } + p_first->p_rlnk = NULL; + } + else { + p_first->p_lnk = NULL; + } + return (p_first); +} + + +/*--------------------------- rt_put_rdy_first ------------------------------*/ + +void rt_put_rdy_first (P_TCB p_task) { + /* Put task identified with "p_task" at the head of the ready list. The */ + /* task must have at least a priority equal to highest priority in list. */ + p_task->p_lnk = os_rdy.p_lnk; + p_task->p_rlnk = NULL; + os_rdy.p_lnk = p_task; +} + + +/*--------------------------- rt_get_same_rdy_prio --------------------------*/ + +P_TCB rt_get_same_rdy_prio (void) { + /* Remove a task of same priority from ready list if any exists. Other- */ + /* wise return NULL. */ + P_TCB p_first; + + p_first = os_rdy.p_lnk; + if (p_first->prio == os_tsk.run->prio) { + os_rdy.p_lnk = os_rdy.p_lnk->p_lnk; + return (p_first); + } + return (NULL); +} + + +/*--------------------------- rt_resort_prio --------------------------------*/ + +void rt_resort_prio (P_TCB p_task) { + /* Re-sort ordered lists after the priority of 'p_task' has changed. */ + P_TCB p_CB; + + if (p_task->p_rlnk == NULL) { + if (p_task->state == READY) { + /* Task is chained into READY list. */ + p_CB = (P_TCB)&os_rdy; + goto res; + } + } + else { + p_CB = p_task->p_rlnk; + while (p_CB->cb_type == TCB) { + /* Find a header of this task chain list. */ + p_CB = p_CB->p_rlnk; + } +res:rt_rmv_list (p_task); + rt_put_prio ((P_XCB)p_CB, p_task); + } +} + + +/*--------------------------- rt_put_dly ------------------------------------*/ + +void rt_put_dly (P_TCB p_task, U16 delay) { + /* Put a task identified with "p_task" into chained delay wait list using */ + /* a delay value of "delay". */ + P_TCB p; + U32 delta,idelay = delay; + + p = (P_TCB)&os_dly; + if (p->p_dlnk == NULL) { + /* Delay list empty */ + delta = 0; + goto last; + } + delta = os_dly.delta_time; + while (delta < idelay) { + if (p->p_dlnk == NULL) { + /* End of list found */ +last: p_task->p_dlnk = NULL; + p->p_dlnk = p_task; + p_task->p_blnk = p; + p->delta_time = (U16)(idelay - delta); + p_task->delta_time = 0; + return; + } + p = p->p_dlnk; + delta += p->delta_time; + } + /* Right place found */ + p_task->p_dlnk = p->p_dlnk; + p->p_dlnk = p_task; + p_task->p_blnk = p; + if (p_task->p_dlnk != NULL) { + p_task->p_dlnk->p_blnk = p_task; + } + p_task->delta_time = (U16)(delta - idelay); + p->delta_time -= p_task->delta_time; +} + + +/*--------------------------- rt_dec_dly ------------------------------------*/ + +void rt_dec_dly (void) { + /* Decrement delta time of list head: remove tasks having a value of zero.*/ + P_TCB p_rdy; + + if (os_dly.p_dlnk == NULL) { + return; + } + os_dly.delta_time--; + while ((os_dly.delta_time == 0) && (os_dly.p_dlnk != NULL)) { + p_rdy = os_dly.p_dlnk; + if (p_rdy->p_rlnk != NULL) { + /* Task is really enqueued, remove task from semaphore/mailbox */ + /* timeout waiting list. */ + p_rdy->p_rlnk->p_lnk = p_rdy->p_lnk; + if (p_rdy->p_lnk != NULL) { + p_rdy->p_lnk->p_rlnk = p_rdy->p_rlnk; + p_rdy->p_lnk = NULL; + } + p_rdy->p_rlnk = NULL; + } + rt_put_prio (&os_rdy, p_rdy); + os_dly.delta_time = p_rdy->delta_time; + if (p_rdy->state == WAIT_ITV) { + /* Calculate the next time for interval wait. */ + p_rdy->delta_time = p_rdy->interval_time + (U16)os_time; + } + p_rdy->state = READY; + os_dly.p_dlnk = p_rdy->p_dlnk; + if (p_rdy->p_dlnk != NULL) { + p_rdy->p_dlnk->p_blnk = (P_TCB)&os_dly; + p_rdy->p_dlnk = NULL; + } + p_rdy->p_blnk = NULL; + } +} + + +/*--------------------------- rt_rmv_list -----------------------------------*/ + +void rt_rmv_list (P_TCB p_task) { + /* Remove task identified with "p_task" from ready, semaphore or mailbox */ + /* waiting list if enqueued. */ + P_TCB p_b; + + if (p_task->p_rlnk != NULL) { + /* A task is enqueued in semaphore / mailbox waiting list. */ + p_task->p_rlnk->p_lnk = p_task->p_lnk; + if (p_task->p_lnk != NULL) { + p_task->p_lnk->p_rlnk = p_task->p_rlnk; + } + return; + } + + p_b = (P_TCB)&os_rdy; + while (p_b != NULL) { + /* Search the ready list for task "p_task" */ + if (p_b->p_lnk == p_task) { + p_b->p_lnk = p_task->p_lnk; + return; + } + p_b = p_b->p_lnk; + } +} + + +/*--------------------------- rt_rmv_dly ------------------------------------*/ + +void rt_rmv_dly (P_TCB p_task) { + /* Remove task identified with "p_task" from delay list if enqueued. */ + P_TCB p_b; + + p_b = p_task->p_blnk; + if (p_b != NULL) { + /* Task is really enqueued */ + p_b->p_dlnk = p_task->p_dlnk; + if (p_task->p_dlnk != NULL) { + /* 'p_task' is in the middle of list */ + p_b->delta_time += p_task->delta_time; + p_task->p_dlnk->p_blnk = p_b; + p_task->p_dlnk = NULL; + } + else { + /* 'p_task' is at the end of list */ + p_b->delta_time = 0; + } + p_task->p_blnk = NULL; + } +} + + +/*--------------------------- rt_psq_enq ------------------------------------*/ + +void rt_psq_enq (OS_ID entry, U32 arg) { + /* Insert post service request "entry" into ps-queue. */ + U32 idx; + + idx = rt_inc_qi (os_psq->size, &os_psq->count, &os_psq->first); + if (idx < os_psq->size) { + os_psq->q[idx].id = entry; + os_psq->q[idx].arg = arg; + } + else { + os_error (OS_ERR_FIFO_OVF); + } +} + + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_List.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_List.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,67 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_LIST.H + * Purpose: Functions for the management of different lists + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Definitions */ + +/* Values for 'cb_type' */ +#define TCB 0 +#define MCB 1 +#define SCB 2 +#define MUCB 3 +#define HCB 4 + +/* Variables */ +extern struct OS_XCB os_rdy; +extern struct OS_XCB os_dly; + +/* Functions */ +extern void rt_put_prio (P_XCB p_CB, P_TCB p_task); +extern P_TCB rt_get_first (P_XCB p_CB); +extern void rt_put_rdy_first (P_TCB p_task); +extern P_TCB rt_get_same_rdy_prio (void); +extern void rt_resort_prio (P_TCB p_task); +extern void rt_put_dly (P_TCB p_task, U16 delay); +extern void rt_dec_dly (void); +extern void rt_rmv_list (P_TCB p_task); +extern void rt_rmv_dly (P_TCB p_task); +extern void rt_psq_enq (OS_ID entry, U32 arg); + +/* This is a fast macro generating in-line code */ +#define rt_rdy_prio(void) (os_rdy.p_lnk->prio) + + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Mailbox.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Mailbox.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,296 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_MAILBOX.C + * Purpose: Implements waits and wake-ups for mailbox messages + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_System.h" +#include "rt_List.h" +#include "rt_Mailbox.h" +#include "rt_MemBox.h" +#include "rt_Task.h" +#ifdef __CORTEX_A9 +#include "rt_HAL_CA.h" +#else +#include "rt_HAL_CM.h" +#endif + + +/*---------------------------------------------------------------------------- + * Functions + *---------------------------------------------------------------------------*/ + + +/*--------------------------- rt_mbx_init -----------------------------------*/ + +void rt_mbx_init (OS_ID mailbox, U16 mbx_size) { + /* Initialize a mailbox */ + P_MCB p_MCB = mailbox; + + p_MCB->cb_type = MCB; + p_MCB->state = 0; + p_MCB->isr_st = 0; + p_MCB->p_lnk = NULL; + p_MCB->first = 0; + p_MCB->last = 0; + p_MCB->count = 0; + p_MCB->size = (mbx_size + sizeof(void *) - sizeof(struct OS_MCB)) / + (U32)sizeof (void *); +} + + +/*--------------------------- rt_mbx_send -----------------------------------*/ + +OS_RESULT rt_mbx_send (OS_ID mailbox, void *p_msg, U16 timeout) { + /* Send message to a mailbox */ + P_MCB p_MCB = mailbox; + P_TCB p_TCB; + + if ((p_MCB->p_lnk != NULL) && (p_MCB->state == 1)) { + /* A task is waiting for message */ + p_TCB = rt_get_first ((P_XCB)p_MCB); +#ifdef __CMSIS_RTOS + rt_ret_val2(p_TCB, 0x10/*osEventMessage*/, (U32)p_msg); +#else + *p_TCB->msg = p_msg; + rt_ret_val (p_TCB, OS_R_MBX); +#endif + rt_rmv_dly (p_TCB); + rt_dispatch (p_TCB); + } + else { + /* Store message in mailbox queue */ + if (p_MCB->count == p_MCB->size) { + /* No free message entry, wait for one. If message queue is full, */ + /* then no task is waiting for message. The 'p_MCB->p_lnk' list */ + /* pointer can now be reused for send message waits task list. */ + if (timeout == 0) { + return (OS_R_TMO); + } + if (p_MCB->p_lnk != NULL) { + rt_put_prio ((P_XCB)p_MCB, os_tsk.run); + } + else { + p_MCB->p_lnk = os_tsk.run; + os_tsk.run->p_lnk = NULL; + os_tsk.run->p_rlnk = (P_TCB)p_MCB; + /* Task is waiting to send a message */ + p_MCB->state = 2; + } + os_tsk.run->msg = p_msg; + rt_block (timeout, WAIT_MBX); + return (OS_R_TMO); + } + /* Yes, there is a free entry in a mailbox. */ + p_MCB->msg[p_MCB->first] = p_msg; + rt_inc (&p_MCB->count); + if (++p_MCB->first == p_MCB->size) { + p_MCB->first = 0; + } + } + return (OS_R_OK); +} + + +/*--------------------------- rt_mbx_wait -----------------------------------*/ + +OS_RESULT rt_mbx_wait (OS_ID mailbox, void **message, U16 timeout) { + /* Receive a message; possibly wait for it */ + P_MCB p_MCB = mailbox; + P_TCB p_TCB; + + /* If a message is available in the fifo buffer */ + /* remove it from the fifo buffer and return. */ + if (p_MCB->count) { + *message = p_MCB->msg[p_MCB->last]; + if (++p_MCB->last == p_MCB->size) { + p_MCB->last = 0; + } + if ((p_MCB->p_lnk != NULL) && (p_MCB->state == 2)) { + /* A task is waiting to send message */ + p_TCB = rt_get_first ((P_XCB)p_MCB); +#ifdef __CMSIS_RTOS + rt_ret_val(p_TCB, 0/*osOK*/); +#else + rt_ret_val(p_TCB, OS_R_OK); +#endif + p_MCB->msg[p_MCB->first] = p_TCB->msg; + if (++p_MCB->first == p_MCB->size) { + p_MCB->first = 0; + } + rt_rmv_dly (p_TCB); + rt_dispatch (p_TCB); + } + else { + rt_dec (&p_MCB->count); + } + return (OS_R_OK); + } + /* No message available: wait for one */ + if (timeout == 0) { + return (OS_R_TMO); + } + if (p_MCB->p_lnk != NULL) { + rt_put_prio ((P_XCB)p_MCB, os_tsk.run); + } + else { + p_MCB->p_lnk = os_tsk.run; + os_tsk.run->p_lnk = NULL; + os_tsk.run->p_rlnk = (P_TCB)p_MCB; + /* Task is waiting to receive a message */ + p_MCB->state = 1; + } + rt_block(timeout, WAIT_MBX); +#ifndef __CMSIS_RTOS + os_tsk.run->msg = message; +#endif + return (OS_R_TMO); +} + + +/*--------------------------- rt_mbx_check ----------------------------------*/ + +OS_RESULT rt_mbx_check (OS_ID mailbox) { + /* Check for free space in a mailbox. Returns the number of messages */ + /* that can be stored to a mailbox. It returns 0 when mailbox is full. */ + P_MCB p_MCB = mailbox; + + return (p_MCB->size - p_MCB->count); +} + + +/*--------------------------- isr_mbx_send ----------------------------------*/ + +void isr_mbx_send (OS_ID mailbox, void *p_msg) { + /* Same function as "os_mbx_send", but to be called by ISRs. */ + P_MCB p_MCB = mailbox; + + rt_psq_enq (p_MCB, (U32)p_msg); + rt_psh_req (); +} + + +/*--------------------------- isr_mbx_receive -------------------------------*/ + +OS_RESULT isr_mbx_receive (OS_ID mailbox, void **message) { + /* Receive a message in the interrupt function. The interrupt function */ + /* should not wait for a message since this would block the rtx os. */ + P_MCB p_MCB = mailbox; + + if (p_MCB->count) { + /* A message is available in the fifo buffer. */ + *message = p_MCB->msg[p_MCB->last]; + if (p_MCB->state == 2) { + /* A task is locked waiting to send message */ + rt_psq_enq (p_MCB, 0); + rt_psh_req (); + } + rt_dec (&p_MCB->count); + if (++p_MCB->last == p_MCB->size) { + p_MCB->last = 0; + } + return (OS_R_MBX); + } + return (OS_R_OK); +} + + +/*--------------------------- rt_mbx_psh ------------------------------------*/ + +void rt_mbx_psh (P_MCB p_CB, void *p_msg) { + /* Store the message to the mailbox queue or pass it to task directly. */ + P_TCB p_TCB; + void *mem; + + if (p_CB->p_lnk != NULL) switch (p_CB->state) { +#ifdef __CMSIS_RTOS + case 3: + /* Task is waiting to allocate memory, remove it from the waiting list */ + mem = rt_alloc_box(p_msg); + if (mem == NULL) break; + p_TCB = rt_get_first ((P_XCB)p_CB); + rt_ret_val(p_TCB, (U32)mem); + p_TCB->state = READY; + rt_rmv_dly (p_TCB); + rt_put_prio (&os_rdy, p_TCB); + break; +#endif + case 2: + /* Task is waiting to send a message, remove it from the waiting list */ + p_TCB = rt_get_first ((P_XCB)p_CB); +#ifdef __CMSIS_RTOS + rt_ret_val(p_TCB, 0/*osOK*/); +#else + rt_ret_val(p_TCB, OS_R_OK); +#endif + p_CB->msg[p_CB->first] = p_TCB->msg; + rt_inc (&p_CB->count); + if (++p_CB->first == p_CB->size) { + p_CB->first = 0; + } + p_TCB->state = READY; + rt_rmv_dly (p_TCB); + rt_put_prio (&os_rdy, p_TCB); + break; + case 1: + /* Task is waiting for a message, pass the message to the task directly */ + p_TCB = rt_get_first ((P_XCB)p_CB); +#ifdef __CMSIS_RTOS + rt_ret_val2(p_TCB, 0x10/*osEventMessage*/, (U32)p_msg); +#else + *p_TCB->msg = p_msg; + rt_ret_val (p_TCB, OS_R_MBX); +#endif + p_TCB->state = READY; + rt_rmv_dly (p_TCB); + rt_put_prio (&os_rdy, p_TCB); + break; + } else { + /* No task is waiting for a message, store it to the mailbox queue */ + if (p_CB->count < p_CB->size) { + p_CB->msg[p_CB->first] = p_msg; + rt_inc (&p_CB->count); + if (++p_CB->first == p_CB->size) { + p_CB->first = 0; + } + } + else { + os_error (OS_ERR_MBX_OVF); + } + } +} + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Mailbox.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Mailbox.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,48 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_MAILBOX.H + * Purpose: Implements waits and wake-ups for mailbox messages + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Functions */ +extern void rt_mbx_init (OS_ID mailbox, U16 mbx_size); +extern OS_RESULT rt_mbx_send (OS_ID mailbox, void *p_msg, U16 timeout); +extern OS_RESULT rt_mbx_wait (OS_ID mailbox, void **message, U16 timeout); +extern OS_RESULT rt_mbx_check (OS_ID mailbox); +extern void isr_mbx_send (OS_ID mailbox, void *p_msg); +extern OS_RESULT isr_mbx_receive (OS_ID mailbox, void **message); +extern void rt_mbx_psh (P_MCB p_CB, void *p_msg); + + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_MemBox.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_MemBox.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,170 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_MEMBOX.C + * Purpose: Interface functions for fixed memory block management system + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_System.h" +#include "rt_MemBox.h" +#ifdef __CORTEX_A9 +#include "rt_HAL_CA.h" +#else +#include "rt_HAL_CM.h" +#endif + +/*---------------------------------------------------------------------------- + * Global Functions + *---------------------------------------------------------------------------*/ + + +/*--------------------------- _init_box -------------------------------------*/ + +int _init_box (void *box_mem, U32 box_size, U32 blk_size) { + /* Initialize memory block system, returns 0 if OK, 1 if fails. */ + void *end; + void *blk; + void *next; + U32 sizeof_bm; + + /* Create memory structure. */ + if (blk_size & BOX_ALIGN_8) { + /* Memory blocks 8-byte aligned. */ + blk_size = ((blk_size & ~BOX_ALIGN_8) + 7) & ~7; + sizeof_bm = (sizeof (struct OS_BM) + 7) & ~7; + } + else { + /* Memory blocks 4-byte aligned. */ + blk_size = (blk_size + 3) & ~3; + sizeof_bm = sizeof (struct OS_BM); + } + if (blk_size == 0) { + return (1); + } + if ((blk_size + sizeof_bm) > box_size) { + return (1); + } + /* Create a Memory structure. */ + blk = ((U8 *) box_mem) + sizeof_bm; + ((P_BM) box_mem)->free = blk; + end = ((U8 *) box_mem) + box_size; + ((P_BM) box_mem)->end = end; + ((P_BM) box_mem)->blk_size = blk_size; + + /* Link all free blocks using offsets. */ + end = ((U8 *) end) - blk_size; + while (1) { + next = ((U8 *) blk) + blk_size; + if (next > end) break; + *((void **)blk) = next; + blk = next; + } + /* end marker */ + *((void **)blk) = 0; + return (0); +} + +/*--------------------------- rt_alloc_box ----------------------------------*/ + +void *rt_alloc_box (void *box_mem) { + /* Allocate a memory block and return start address. */ + void **free; +#ifndef __USE_EXCLUSIVE_ACCESS + int irq_dis; + + irq_dis = __disable_irq (); + free = ((P_BM) box_mem)->free; + if (free) { + ((P_BM) box_mem)->free = *free; + } + if (!irq_dis) __enable_irq (); +#else + do { + if ((free = (void **)__ldrex(&((P_BM) box_mem)->free)) == 0) { + __clrex(); + break; + } + } while (__strex((U32)*free, &((P_BM) box_mem)->free)); +#endif + return (free); +} + + +/*--------------------------- _calloc_box -----------------------------------*/ + +void *_calloc_box (void *box_mem) { + /* Allocate a 0-initialized memory block and return start address. */ + void *free; + U32 *p; + U32 i; + + free = _alloc_box (box_mem); + if (free) { + p = free; + for (i = ((P_BM) box_mem)->blk_size; i; i -= 4) { + *p = 0; + p++; + } + } + return (free); +} + + +/*--------------------------- rt_free_box -----------------------------------*/ + +int rt_free_box (void *box_mem, void *box) { + /* Free a memory block, returns 0 if OK, 1 if box does not belong to box_mem */ +#ifndef __USE_EXCLUSIVE_ACCESS + int irq_dis; +#endif + + if (box < box_mem || box >= ((P_BM) box_mem)->end) { + return (1); + } + +#ifndef __USE_EXCLUSIVE_ACCESS + irq_dis = __disable_irq (); + *((void **)box) = ((P_BM) box_mem)->free; + ((P_BM) box_mem)->free = box; + if (!irq_dis) __enable_irq (); +#else + do { + *((void **)box) = (void *)__ldrex(&((P_BM) box_mem)->free); + } while (__strex ((U32)box, &((P_BM) box_mem)->free)); +#endif + return (0); +} + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_MemBox.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_MemBox.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,46 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_MEMBOX.H + * Purpose: Interface functions for fixed memory block management system + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Functions */ +#define rt_init_box _init_box +#define rt_calloc_box _calloc_box +extern int _init_box (void *box_mem, U32 box_size, U32 blk_size); +extern void *rt_alloc_box (void *box_mem); +extern void * _calloc_box (void *box_mem); +extern int rt_free_box (void *box_mem, void *box); + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Memory.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Memory.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,140 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_MEMORY.C + * Purpose: Interface functions for Dynamic Memory Management System + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "rt_Memory.h" + + +/* Functions */ + +// Initialize Dynamic Memory pool +// Parameters: +// pool: Pointer to memory pool +// size: Size of memory pool in bytes +// Return: 0 - OK, 1 - Error + +int rt_init_mem (void *pool, U32 size) { + MEMP *ptr; + + if ((pool == NULL) || (size < sizeof(MEMP))) return (1); + + ptr = (MEMP *)pool; + ptr->next = (MEMP *)((U32)pool + size - sizeof(MEMP *)); + ptr->next->next = NULL; + ptr->len = 0; + + return (0); +} + +// Allocate Memory from Memory pool +// Parameters: +// pool: Pointer to memory pool +// size: Size of memory in bytes to allocate +// Return: Pointer to allocated memory + +void *rt_alloc_mem (void *pool, U32 size) { + MEMP *p, *p_search, *p_new; + U32 hole_size; + + if ((pool == NULL) || (size == 0)) return NULL; + + /* Add header offset to 'size' */ + size += sizeof(MEMP); + /* Make sure that block is 4-byte aligned */ + size = (size + 3) & ~3; + + p_search = (MEMP *)pool; + while (1) { + hole_size = (U32)p_search->next - (U32)p_search; + hole_size -= p_search->len; + /* Check if hole size is big enough */ + if (hole_size >= size) break; + p_search = p_search->next; + if (p_search->next == NULL) { + /* Failed, we are at the end of the list */ + return NULL; + } + } + + if (p_search->len == 0) { + /* No block is allocated, set the Length of the first element */ + p_search->len = size; + p = (MEMP *)(((U32)p_search) + sizeof(MEMP)); + } else { + /* Insert new list element into the memory list */ + p_new = (MEMP *)((U32)p_search + p_search->len); + p_new->next = p_search->next; + p_new->len = size; + p_search->next = p_new; + p = (MEMP *)(((U32)p_new) + sizeof(MEMP)); + } + + return (p); +} + +// Free Memory and return it to Memory pool +// Parameters: +// pool: Pointer to memory pool +// mem: Pointer to memory to free +// Return: 0 - OK, 1 - Error + +int rt_free_mem (void *pool, void *mem) { + MEMP *p_search, *p_prev, *p_return; + + if ((pool == NULL) || (mem == NULL)) return (1); + + p_return = (MEMP *)((U32)mem - sizeof(MEMP)); + + /* Set list header */ + p_prev = NULL; + p_search = (MEMP *)pool; + while (p_search != p_return) { + p_prev = p_search; + p_search = p_search->next; + if (p_search == NULL) { + /* Valid Memory block not found */ + return (1); + } + } + + if (p_prev == NULL) { + /* First block to be released, only set length to 0 */ + p_search->len = 0; + } else { + /* Discard block from chain list */ + p_prev->next = p_search->next; + } + + return (0); +}
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Memory.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Memory.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,44 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_MEMORY.H + * Purpose: Interface functions for Dynamic Memory Management System + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Types */ +typedef struct mem { /* << Memory Pool management struct >> */ + struct mem *next; /* Next Memory Block in the list */ + U32 len; /* Length of data block */ +} MEMP; + +/* Functions */ +extern int rt_init_mem (void *pool, U32 size); +extern void *rt_alloc_mem (void *pool, U32 size); +extern int rt_free_mem (void *pool, void *mem);
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Mutex.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Mutex.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,204 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_MUTEX.C + * Purpose: Implements mutex synchronization objects + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_List.h" +#include "rt_Task.h" +#include "rt_Mutex.h" +#ifdef __CORTEX_A9 +#include "rt_HAL_CA.h" +#else +#include "rt_HAL_CM.h" +#endif + + +/*---------------------------------------------------------------------------- + * Functions + *---------------------------------------------------------------------------*/ + + +/*--------------------------- rt_mut_init -----------------------------------*/ + +void rt_mut_init (OS_ID mutex) { + /* Initialize a mutex object */ + P_MUCB p_MCB = mutex; + + p_MCB->cb_type = MUCB; + p_MCB->prio = 0; + p_MCB->level = 0; + p_MCB->p_lnk = NULL; + p_MCB->owner = NULL; +} + + +/*--------------------------- rt_mut_delete ---------------------------------*/ + +#ifdef __CMSIS_RTOS +OS_RESULT rt_mut_delete (OS_ID mutex) { + /* Delete a mutex object */ + P_MUCB p_MCB = mutex; + P_TCB p_TCB; + + __DMB(); + /* Restore owner task's priority. */ + if (p_MCB->level != 0) { + p_MCB->owner->prio = p_MCB->prio; + if (p_MCB->owner != os_tsk.run) { + rt_resort_prio (p_MCB->owner); + } + } + + while (p_MCB->p_lnk != NULL) { + /* A task is waiting for mutex. */ + p_TCB = rt_get_first ((P_XCB)p_MCB); + rt_ret_val(p_TCB, 0/*osOK*/); + rt_rmv_dly(p_TCB); + p_TCB->state = READY; + rt_put_prio (&os_rdy, p_TCB); + } + + if (os_rdy.p_lnk && (os_rdy.p_lnk->prio > os_tsk.run->prio)) { + /* preempt running task */ + rt_put_prio (&os_rdy, os_tsk.run); + os_tsk.run->state = READY; + rt_dispatch (NULL); + } + + p_MCB->cb_type = 0; + + return (OS_R_OK); +} +#endif + + +/*--------------------------- rt_mut_release --------------------------------*/ + +OS_RESULT rt_mut_release (OS_ID mutex) { + /* Release a mutex object */ + P_MUCB p_MCB = mutex; + P_TCB p_TCB; + + if (p_MCB->level == 0 || p_MCB->owner != os_tsk.run) { + /* Unbalanced mutex release or task is not the owner */ + return (OS_R_NOK); + } + __DMB(); + if (--p_MCB->level != 0) { + return (OS_R_OK); + } + /* Restore owner task's priority. */ + os_tsk.run->prio = p_MCB->prio; + if (p_MCB->p_lnk != NULL) { + /* A task is waiting for mutex. */ + p_TCB = rt_get_first ((P_XCB)p_MCB); +#ifdef __CMSIS_RTOS + rt_ret_val(p_TCB, 0/*osOK*/); +#else + rt_ret_val(p_TCB, OS_R_MUT); +#endif + rt_rmv_dly (p_TCB); + /* A waiting task becomes the owner of this mutex. */ + p_MCB->level = 1; + p_MCB->owner = p_TCB; + p_MCB->prio = p_TCB->prio; + /* Priority inversion, check which task continues. */ + if (os_tsk.run->prio >= rt_rdy_prio()) { + rt_dispatch (p_TCB); + } + else { + /* Ready task has higher priority than running task. */ + rt_put_prio (&os_rdy, os_tsk.run); + rt_put_prio (&os_rdy, p_TCB); + os_tsk.run->state = READY; + p_TCB->state = READY; + rt_dispatch (NULL); + } + } + else { + /* Check if own priority raised by priority inversion. */ + if (rt_rdy_prio() > os_tsk.run->prio) { + rt_put_prio (&os_rdy, os_tsk.run); + os_tsk.run->state = READY; + rt_dispatch (NULL); + } + } + return (OS_R_OK); +} + + +/*--------------------------- rt_mut_wait -----------------------------------*/ + +OS_RESULT rt_mut_wait (OS_ID mutex, U16 timeout) { + /* Wait for a mutex, continue when mutex is free. */ + P_MUCB p_MCB = mutex; + + if (p_MCB->level == 0) { + p_MCB->owner = os_tsk.run; + p_MCB->prio = os_tsk.run->prio; + goto inc; + } + if (p_MCB->owner == os_tsk.run) { + /* OK, running task is the owner of this mutex. */ +inc:p_MCB->level++; + __DMB(); + return (OS_R_OK); + } + /* Mutex owned by another task, wait until released. */ + if (timeout == 0) { + return (OS_R_TMO); + } + /* Raise the owner task priority if lower than current priority. */ + /* This priority inversion is called priority inheritance. */ + if (p_MCB->prio < os_tsk.run->prio) { + p_MCB->owner->prio = os_tsk.run->prio; + rt_resort_prio (p_MCB->owner); + } + if (p_MCB->p_lnk != NULL) { + rt_put_prio ((P_XCB)p_MCB, os_tsk.run); + } + else { + p_MCB->p_lnk = os_tsk.run; + os_tsk.run->p_lnk = NULL; + os_tsk.run->p_rlnk = (P_TCB)p_MCB; + } + rt_block(timeout, WAIT_MUT); + return (OS_R_TMO); +} + + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Mutex.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Mutex.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,44 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_MUTEX.H + * Purpose: Implements mutex synchronization objects + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Functions */ +extern void rt_mut_init (OS_ID mutex); +extern OS_RESULT rt_mut_delete (OS_ID mutex); +extern OS_RESULT rt_mut_release (OS_ID mutex); +extern OS_RESULT rt_mut_wait (OS_ID mutex, U16 timeout); + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Robin.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Robin.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,88 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_ROBIN.C + * Purpose: Round Robin Task switching + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_List.h" +#include "rt_Task.h" +#include "rt_Time.h" +#include "rt_Robin.h" +#ifdef __CORTEX_A9 +#include "rt_HAL_CA.h" +#else +#include "rt_HAL_CM.h" +#endif + +/*---------------------------------------------------------------------------- + * Global Variables + *---------------------------------------------------------------------------*/ + +struct OS_ROBIN os_robin; + + +/*---------------------------------------------------------------------------- + * Global Functions + *---------------------------------------------------------------------------*/ + +/*--------------------------- rt_init_robin ---------------------------------*/ + +__weak void rt_init_robin (void) { + /* Initialize Round Robin variables. */ + os_robin.task = NULL; + os_robin.tout = (U16)os_rrobin; +} + +/*--------------------------- rt_chk_robin ----------------------------------*/ + +__weak void rt_chk_robin (void) { + /* Check if Round Robin timeout expired and switch to the next ready task.*/ + P_TCB p_new; + + if (os_robin.task != os_rdy.p_lnk) { + /* New task was suspended, reset Round Robin timeout. */ + os_robin.task = os_rdy.p_lnk; + os_robin.time = (U16)os_time + os_robin.tout - 1; + } + if (os_robin.time == (U16)os_time) { + /* Round Robin timeout has expired, swap Robin tasks. */ + os_robin.task = NULL; + p_new = rt_get_first (&os_rdy); + rt_put_prio ((P_XCB)&os_rdy, p_new); + } +} + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Robin.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Robin.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,45 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_ROBIN.H + * Purpose: Round Robin Task switching definitions + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Variables */ +extern struct OS_ROBIN os_robin; + +/* Functions */ +extern void rt_init_robin (void); +extern void rt_chk_robin (void); + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Semaphore.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Semaphore.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,191 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_SEMAPHORE.C + * Purpose: Implements binary and counting semaphores + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_System.h" +#include "rt_List.h" +#include "rt_Task.h" +#include "rt_Semaphore.h" +#ifdef __CORTEX_A9 +#include "rt_HAL_CA.h" +#else +#include "rt_HAL_CM.h" +#endif + + +/*---------------------------------------------------------------------------- + * Functions + *---------------------------------------------------------------------------*/ + + +/*--------------------------- rt_sem_init -----------------------------------*/ + +void rt_sem_init (OS_ID semaphore, U16 token_count) { + /* Initialize a semaphore */ + P_SCB p_SCB = semaphore; + + p_SCB->cb_type = SCB; + p_SCB->p_lnk = NULL; + p_SCB->tokens = token_count; +} + + +/*--------------------------- rt_sem_delete ---------------------------------*/ + +#ifdef __CMSIS_RTOS +OS_RESULT rt_sem_delete (OS_ID semaphore) { + /* Delete semaphore */ + P_SCB p_SCB = semaphore; + P_TCB p_TCB; + + __DMB(); + while (p_SCB->p_lnk != NULL) { + /* A task is waiting for token */ + p_TCB = rt_get_first ((P_XCB)p_SCB); + rt_ret_val(p_TCB, 0); + rt_rmv_dly(p_TCB); + p_TCB->state = READY; + rt_put_prio (&os_rdy, p_TCB); + } + + if (os_rdy.p_lnk && (os_rdy.p_lnk->prio > os_tsk.run->prio)) { + /* preempt running task */ + rt_put_prio (&os_rdy, os_tsk.run); + os_tsk.run->state = READY; + rt_dispatch (NULL); + } + + p_SCB->cb_type = 0; + + return (OS_R_OK); +} +#endif + + +/*--------------------------- rt_sem_send -----------------------------------*/ + +OS_RESULT rt_sem_send (OS_ID semaphore) { + /* Return a token to semaphore */ + P_SCB p_SCB = semaphore; + P_TCB p_TCB; + + __DMB(); + if (p_SCB->p_lnk != NULL) { + /* A task is waiting for token */ + p_TCB = rt_get_first ((P_XCB)p_SCB); +#ifdef __CMSIS_RTOS + rt_ret_val(p_TCB, 1); +#else + rt_ret_val(p_TCB, OS_R_SEM); +#endif + rt_rmv_dly (p_TCB); + rt_dispatch (p_TCB); + } + else { + /* Store token. */ + p_SCB->tokens++; + } + return (OS_R_OK); +} + + +/*--------------------------- rt_sem_wait -----------------------------------*/ + +OS_RESULT rt_sem_wait (OS_ID semaphore, U16 timeout) { + /* Obtain a token; possibly wait for it */ + P_SCB p_SCB = semaphore; + + if (p_SCB->tokens) { + p_SCB->tokens--; + __DMB(); + return (OS_R_OK); + } + /* No token available: wait for one */ + if (timeout == 0) { + return (OS_R_TMO); + } + if (p_SCB->p_lnk != NULL) { + rt_put_prio ((P_XCB)p_SCB, os_tsk.run); + } + else { + p_SCB->p_lnk = os_tsk.run; + os_tsk.run->p_lnk = NULL; + os_tsk.run->p_rlnk = (P_TCB)p_SCB; + } + rt_block(timeout, WAIT_SEM); + return (OS_R_TMO); +} + + +/*--------------------------- isr_sem_send ----------------------------------*/ + +void isr_sem_send (OS_ID semaphore) { + /* Same function as "os_sem"send", but to be called by ISRs */ + P_SCB p_SCB = semaphore; + + rt_psq_enq (p_SCB, 0); + rt_psh_req (); +} + + +/*--------------------------- rt_sem_psh ------------------------------------*/ + +void rt_sem_psh (P_SCB p_CB) { + /* Check if task has to be waken up */ + P_TCB p_TCB; + + __DMB(); + if (p_CB->p_lnk != NULL) { + /* A task is waiting for token */ + p_TCB = rt_get_first ((P_XCB)p_CB); + rt_rmv_dly (p_TCB); + p_TCB->state = READY; +#ifdef __CMSIS_RTOS + rt_ret_val(p_TCB, 1); +#else + rt_ret_val(p_TCB, OS_R_SEM); +#endif + rt_put_prio (&os_rdy, p_TCB); + } + else { + /* Store token */ + p_CB->tokens++; + } +} + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Semaphore.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Semaphore.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,46 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_SEMAPHORE.H + * Purpose: Implements binary and counting semaphores + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Functions */ +extern void rt_sem_init (OS_ID semaphore, U16 token_count); +extern OS_RESULT rt_sem_delete(OS_ID semaphore); +extern OS_RESULT rt_sem_send (OS_ID semaphore); +extern OS_RESULT rt_sem_wait (OS_ID semaphore, U16 timeout); +extern void isr_sem_send (OS_ID semaphore); +extern void rt_sem_psh (P_SCB p_CB); + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_System.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_System.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,304 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_SYSTEM.C + * Purpose: System Task Manager + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_Task.h" +#include "rt_System.h" +#include "rt_Event.h" +#include "rt_List.h" +#include "rt_Mailbox.h" +#include "rt_Semaphore.h" +#include "rt_Time.h" +#include "rt_Timer.h" +#include "rt_Robin.h" +#ifdef __CORTEX_A9 +#include "rt_HAL_CA.h" +#else +#include "rt_HAL_CM.h" +#endif + +/*---------------------------------------------------------------------------- + * Global Variables + *---------------------------------------------------------------------------*/ + +int os_tick_irqn; + +/*---------------------------------------------------------------------------- + * Local Variables + *---------------------------------------------------------------------------*/ + +static volatile BIT os_lock; +static volatile BIT os_psh_flag; +#ifndef __CORTEX_A9 +static U8 pend_flags; +#endif +/*---------------------------------------------------------------------------- + * Global Functions + *---------------------------------------------------------------------------*/ + +#if defined (__CC_ARM) +__asm void $$RTX$$version (void) { + /* Export a version number symbol for a version control. */ + + EXPORT __RL_RTX_VER + +__RL_RTX_VER EQU 0x450 +} +#endif + + +/*--------------------------- rt_suspend ------------------------------------*/ + +U32 rt_suspend (void) { + /* Suspend OS scheduler */ + U32 delta = 0xFFFF; + + rt_tsk_lock(); + + if (os_dly.p_dlnk) { + delta = os_dly.delta_time; + } +#ifndef __CMSIS_RTOS + if (os_tmr.next) { + if (os_tmr.tcnt < delta) delta = os_tmr.tcnt; + } +#endif + + return (delta); +} + + +/*--------------------------- rt_resume -------------------------------------*/ + +void rt_resume (U32 sleep_time) { + /* Resume OS scheduler after suspend */ + P_TCB next; + U32 delta; + + os_tsk.run->state = READY; + rt_put_rdy_first (os_tsk.run); + + os_robin.task = NULL; + + /* Update delays. */ + if (os_dly.p_dlnk) { + delta = sleep_time; + if (delta >= os_dly.delta_time) { + delta -= os_dly.delta_time; + os_time += os_dly.delta_time; + os_dly.delta_time = 1; + while (os_dly.p_dlnk) { + rt_dec_dly(); + if (delta == 0) break; + delta--; + os_time++; + } + } else { + os_time += delta; + os_dly.delta_time -= delta; + } + } else { + os_time += sleep_time; + } + +#ifndef __CMSIS_RTOS + /* Check the user timers. */ + if (os_tmr.next) { + delta = sleep_time; + if (delta >= os_tmr.tcnt) { + delta -= os_tmr.tcnt; + os_tmr.tcnt = 1; + while (os_tmr.next) { + rt_tmr_tick(); + if (delta == 0) break; + delta--; + } + } else { + os_tmr.tcnt -= delta; + } + } +#endif + + /* Switch back to highest ready task */ + next = rt_get_first (&os_rdy); + rt_switch_req (next); + + rt_tsk_unlock(); +} + + +/*--------------------------- rt_tsk_lock -----------------------------------*/ + +void rt_tsk_lock (void) { + /* Prevent task switching by locking out scheduler */ + if (os_tick_irqn < 0) { + OS_LOCK(); + os_lock = __TRUE; + OS_UNPEND (&pend_flags); + } else { + OS_X_LOCK(os_tick_irqn); + os_lock = __TRUE; + OS_X_UNPEND (&pend_flags); + } +} + + +/*--------------------------- rt_tsk_unlock ---------------------------------*/ + +void rt_tsk_unlock (void) { + /* Unlock scheduler and re-enable task switching */ + if (os_tick_irqn < 0) { + OS_UNLOCK(); + os_lock = __FALSE; + OS_PEND (pend_flags, os_psh_flag); + os_psh_flag = __FALSE; + } else { + OS_X_UNLOCK(os_tick_irqn); + os_lock = __FALSE; + OS_X_PEND (pend_flags, os_psh_flag); + os_psh_flag = __FALSE; + } +} + + +/*--------------------------- rt_psh_req ------------------------------------*/ + +void rt_psh_req (void) { + /* Initiate a post service handling request if required. */ + if (os_lock == __FALSE) { + OS_PEND_IRQ (); + } + else { + os_psh_flag = __TRUE; + } +} + + +/*--------------------------- rt_pop_req ------------------------------------*/ + +void rt_pop_req (void) { + /* Process an ISR post service requests. */ + struct OS_XCB *p_CB; + P_TCB next; + U32 idx; + + os_tsk.run->state = READY; + rt_put_rdy_first (os_tsk.run); + + idx = os_psq->last; + while (os_psq->count) { + p_CB = os_psq->q[idx].id; + if (p_CB->cb_type == TCB) { + /* Is of TCB type */ + rt_evt_psh ((P_TCB)p_CB, (U16)os_psq->q[idx].arg); + } + else if (p_CB->cb_type == MCB) { + /* Is of MCB type */ + rt_mbx_psh ((P_MCB)p_CB, (void *)os_psq->q[idx].arg); + } + else { + /* Must be of SCB type */ + rt_sem_psh ((P_SCB)p_CB); + } + if (++idx == os_psq->size) idx = 0; + rt_dec (&os_psq->count); + } + os_psq->last = idx; + + next = rt_get_first (&os_rdy); + rt_switch_req (next); +} + + +/*--------------------------- os_tick_init ----------------------------------*/ + +__weak int os_tick_init (void) { + /* Initialize SysTick timer as system tick timer. */ + rt_systick_init (); + return (-1); /* Return IRQ number of SysTick timer */ +} + + +/*--------------------------- os_tick_irqack --------------------------------*/ + +__weak void os_tick_irqack (void) { + /* Acknowledge timer interrupt. */ +} + + +/*--------------------------- rt_systick ------------------------------------*/ + +extern void sysTimerTick(void); + +void rt_systick (void) { + /* Check for system clock update, suspend running task. */ + P_TCB next; + + os_tsk.run->state = READY; + rt_put_rdy_first (os_tsk.run); + + /* Check Round Robin timeout. */ + rt_chk_robin (); + + /* Update delays. */ + os_time++; + rt_dec_dly (); + + /* Check the user timers. */ +#ifdef __CMSIS_RTOS + sysTimerTick(); +#else + rt_tmr_tick (); +#endif + + /* Switch back to highest ready task */ + next = rt_get_first (&os_rdy); + rt_switch_req (next); +} + +/*--------------------------- rt_stk_check ----------------------------------*/ + +__weak void rt_stk_check (void) { + /* Check for stack overflow. */ + if ((os_tsk.run->tsk_stack < (U32)os_tsk.run->stack) || + (os_tsk.run->stack[0] != MAGIC_WORD)) { + os_error (OS_ERR_STK_OVF); + } +} + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_System.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_System.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,52 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_SYSTEM.H + * Purpose: System Task Manager definitions + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Variables */ +#define os_psq ((P_PSQ)&os_fifo) +extern int os_tick_irqn; + +/* Functions */ +extern U32 rt_suspend (void); +extern void rt_resume (U32 sleep_time); +extern void rt_tsk_lock (void); +extern void rt_tsk_unlock (void); +extern void rt_psh_req (void); +extern void rt_pop_req (void); +extern void rt_systick (void); +extern void rt_stk_check (void); + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Task.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Task.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,372 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_TASK.C + * Purpose: Task functions and system start up. + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_System.h" +#include "rt_Task.h" +#include "rt_List.h" +#include "rt_MemBox.h" +#include "rt_Robin.h" +#ifdef __CORTEX_A9 +#include "rt_HAL_CA.h" +#else +#include "rt_HAL_CM.h" +#endif + +/*---------------------------------------------------------------------------- + * Global Variables + *---------------------------------------------------------------------------*/ + +/* Running and next task info. */ +struct OS_TSK os_tsk; + +/* Task Control Blocks of idle demon */ +struct OS_TCB os_idle_TCB; + + +/*---------------------------------------------------------------------------- + * Local Functions + *---------------------------------------------------------------------------*/ + +static OS_TID rt_get_TID (void) { + U32 tid; + + for (tid = 1; tid <= os_maxtaskrun; tid++) { + if (os_active_TCB[tid-1] == NULL) { + return ((OS_TID)tid); + } + } + return (0); +} + + +/*--------------------------- rt_init_context -------------------------------*/ + +static void rt_init_context (P_TCB p_TCB, U8 priority, FUNCP task_body) { + /* Initialize general part of the Task Control Block. */ + p_TCB->cb_type = TCB; + p_TCB->state = READY; + p_TCB->prio = priority; + p_TCB->p_lnk = NULL; + p_TCB->p_rlnk = NULL; + p_TCB->p_dlnk = NULL; + p_TCB->p_blnk = NULL; + p_TCB->delta_time = 0; + p_TCB->interval_time = 0; + p_TCB->events = 0; + p_TCB->waits = 0; + p_TCB->stack_frame = 0; + + if (p_TCB->priv_stack == 0) { + /* Allocate the memory space for the stack. */ + p_TCB->stack = rt_alloc_box (mp_stk); + } + rt_init_stack (p_TCB, task_body); +} + + +/*--------------------------- rt_switch_req ---------------------------------*/ + +void rt_switch_req (P_TCB p_new) { + /* Switch to next task (identified by "p_new"). */ + os_tsk.new = p_new; + p_new->state = RUNNING; + DBG_TASK_SWITCH(p_new->task_id); +} + + +/*--------------------------- rt_dispatch -----------------------------------*/ + +void rt_dispatch (P_TCB next_TCB) { + /* Dispatch next task if any identified or dispatch highest ready task */ + /* "next_TCB" identifies a task to run or has value NULL (=no next task) */ + if (next_TCB == NULL) { + /* Running task was blocked: continue with highest ready task */ + next_TCB = rt_get_first (&os_rdy); + rt_switch_req (next_TCB); + } + else { + /* Check which task continues */ + if (next_TCB->prio > os_tsk.run->prio) { + /* preempt running task */ + rt_put_rdy_first (os_tsk.run); + os_tsk.run->state = READY; + rt_switch_req (next_TCB); + } + else { + /* put next task into ready list, no task switch takes place */ + next_TCB->state = READY; + rt_put_prio (&os_rdy, next_TCB); + } + } +} + + +/*--------------------------- rt_block --------------------------------------*/ + +void rt_block (U16 timeout, U8 block_state) { + /* Block running task and choose next ready task. */ + /* "timeout" sets a time-out value or is 0xffff (=no time-out). */ + /* "block_state" defines the appropriate task state */ + P_TCB next_TCB; + + if (timeout) { + if (timeout < 0xffff) { + rt_put_dly (os_tsk.run, timeout); + } + os_tsk.run->state = block_state; + next_TCB = rt_get_first (&os_rdy); + rt_switch_req (next_TCB); + } +} + + +/*--------------------------- rt_tsk_pass -----------------------------------*/ + +void rt_tsk_pass (void) { + /* Allow tasks of same priority level to run cooperatively.*/ + P_TCB p_new; + + p_new = rt_get_same_rdy_prio(); + if (p_new != NULL) { + rt_put_prio ((P_XCB)&os_rdy, os_tsk.run); + os_tsk.run->state = READY; + rt_switch_req (p_new); + } +} + + +/*--------------------------- rt_tsk_self -----------------------------------*/ + +OS_TID rt_tsk_self (void) { + /* Return own task identifier value. */ + if (os_tsk.run == NULL) { + return (0); + } + return (os_tsk.run->task_id); +} + + +/*--------------------------- rt_tsk_prio -----------------------------------*/ + +OS_RESULT rt_tsk_prio (OS_TID task_id, U8 new_prio) { + /* Change execution priority of a task to "new_prio". */ + P_TCB p_task; + + if (task_id == 0) { + /* Change execution priority of calling task. */ + os_tsk.run->prio = new_prio; +run:if (rt_rdy_prio() > new_prio) { + rt_put_prio (&os_rdy, os_tsk.run); + os_tsk.run->state = READY; + rt_dispatch (NULL); + } + return (OS_R_OK); + } + + /* Find the task in the "os_active_TCB" array. */ + if (task_id > os_maxtaskrun || os_active_TCB[task_id-1] == NULL) { + /* Task with "task_id" not found or not started. */ + return (OS_R_NOK); + } + p_task = os_active_TCB[task_id-1]; + p_task->prio = new_prio; + if (p_task == os_tsk.run) { + goto run; + } + rt_resort_prio (p_task); + if (p_task->state == READY) { + /* Task enqueued in a ready list. */ + p_task = rt_get_first (&os_rdy); + rt_dispatch (p_task); + } + return (OS_R_OK); +} + + +/*--------------------------- rt_tsk_create ---------------------------------*/ + +OS_TID rt_tsk_create (FUNCP task, U32 prio_stksz, void *stk, void *argv) { + /* Start a new task declared with "task". */ + P_TCB task_context; + U32 i; + + /* Priority 0 is reserved for idle task! */ + if ((prio_stksz & 0xFF) == 0) { + prio_stksz += 1; + } + task_context = rt_alloc_box (mp_tcb); + if (task_context == NULL) { + return (0); + } + /* If "size != 0" use a private user provided stack. */ + task_context->stack = stk; + task_context->priv_stack = prio_stksz >> 8; + /* Pass parameter 'argv' to 'rt_init_context' */ + task_context->msg = argv; + /* For 'size == 0' system allocates the user stack from the memory pool. */ + rt_init_context (task_context, prio_stksz & 0xFF, task); + + /* Find a free entry in 'os_active_TCB' table. */ + i = rt_get_TID (); + os_active_TCB[i-1] = task_context; + task_context->task_id = i; + DBG_TASK_NOTIFY(task_context, __TRUE); + rt_dispatch (task_context); + return ((OS_TID)i); +} + + +/*--------------------------- rt_tsk_delete ---------------------------------*/ + +OS_RESULT rt_tsk_delete (OS_TID task_id) { + /* Terminate the task identified with "task_id". */ + P_TCB task_context; + + if (task_id == 0 || task_id == os_tsk.run->task_id) { + /* Terminate itself. */ + os_tsk.run->state = INACTIVE; + os_tsk.run->tsk_stack = rt_get_PSP (); + rt_stk_check (); + os_active_TCB[os_tsk.run->task_id-1] = NULL; + rt_free_box (mp_stk, os_tsk.run->stack); + os_tsk.run->stack = NULL; + DBG_TASK_NOTIFY(os_tsk.run, __FALSE); + rt_free_box (mp_tcb, os_tsk.run); + os_tsk.run = NULL; + rt_dispatch (NULL); + /* The program should never come to this point. */ + } + else { + /* Find the task in the "os_active_TCB" array. */ + if (task_id > os_maxtaskrun || os_active_TCB[task_id-1] == NULL) { + /* Task with "task_id" not found or not started. */ + return (OS_R_NOK); + } + task_context = os_active_TCB[task_id-1]; + rt_rmv_list (task_context); + rt_rmv_dly (task_context); + os_active_TCB[task_id-1] = NULL; + rt_free_box (mp_stk, task_context->stack); + task_context->stack = NULL; + DBG_TASK_NOTIFY(task_context, __FALSE); + rt_free_box (mp_tcb, task_context); + } + return (OS_R_OK); +} + + +/*--------------------------- rt_sys_init -----------------------------------*/ + +#ifdef __CMSIS_RTOS +void rt_sys_init (void) { +#else +void rt_sys_init (FUNCP first_task, U32 prio_stksz, void *stk) { +#endif + /* Initialize system and start up task declared with "first_task". */ + U32 i; + + DBG_INIT(); + + /* Initialize dynamic memory and task TCB pointers to NULL. */ + for (i = 0; i < os_maxtaskrun; i++) { + os_active_TCB[i] = NULL; + } + rt_init_box (&mp_tcb, mp_tcb_size, sizeof(struct OS_TCB)); + rt_init_box (&mp_stk, mp_stk_size, BOX_ALIGN_8 | (U16)(os_stackinfo)); + rt_init_box ((U32 *)m_tmr, mp_tmr_size, sizeof(struct OS_TMR)); + + /* Set up TCB of idle demon */ + os_idle_TCB.task_id = 255; + os_idle_TCB.priv_stack = 0; + rt_init_context (&os_idle_TCB, 0, os_idle_demon); + + /* Set up ready list: initially empty */ + os_rdy.cb_type = HCB; + os_rdy.p_lnk = NULL; + /* Set up delay list: initially empty */ + os_dly.cb_type = HCB; + os_dly.p_dlnk = NULL; + os_dly.p_blnk = NULL; + os_dly.delta_time = 0; + + /* Fix SP and system variables to assume idle task is running */ + /* Transform main program into idle task by assuming idle TCB */ +#ifndef __CMSIS_RTOS + rt_set_PSP (os_idle_TCB.tsk_stack+32); +#endif + os_tsk.run = &os_idle_TCB; + os_tsk.run->state = RUNNING; + + /* Initialize ps queue */ + os_psq->first = 0; + os_psq->last = 0; + os_psq->size = os_fifo_size; + + rt_init_robin (); + + /* Initialize SVC and PendSV */ + rt_svc_init (); + +#ifndef __CMSIS_RTOS + /* Initialize and start system clock timer */ + os_tick_irqn = os_tick_init (); + if (os_tick_irqn >= 0) { + OS_X_INIT(os_tick_irqn); + } + + /* Start up first user task before entering the endless loop */ + rt_tsk_create (first_task, prio_stksz, stk, NULL); +#endif +} + + +/*--------------------------- rt_sys_start ----------------------------------*/ + +#ifdef __CMSIS_RTOS +void rt_sys_start (void) { + /* Start system */ + + /* Initialize and start system clock timer */ + os_tick_irqn = os_tick_init (); + if (os_tick_irqn >= 0) { + OS_X_INIT(os_tick_irqn); + } +} +#endif + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Task.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Task.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,87 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_TASK.H + * Purpose: Task functions and system start up. + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Definitions */ + +/* Values for 'state' */ +#define INACTIVE 0 +#define READY 1 +#define RUNNING 2 +#define WAIT_DLY 3 +#define WAIT_ITV 4 +#define WAIT_OR 5 +#define WAIT_AND 6 +#define WAIT_SEM 7 +#define WAIT_MBX 8 +#define WAIT_MUT 9 + +/* Return codes */ +#define OS_R_TMO 0x01 +#define OS_R_EVT 0x02 +#define OS_R_SEM 0x03 +#define OS_R_MBX 0x04 +#define OS_R_MUT 0x05 + +#define OS_R_OK 0x00 +#define OS_R_NOK 0xff + +/* Variables */ +extern struct OS_TSK os_tsk; +extern struct OS_TCB os_idle_TCB; + +/* Functions */ +extern void rt_switch_req (P_TCB p_new); +extern void rt_dispatch (P_TCB next_TCB); +extern void rt_block (U16 timeout, U8 block_state); +extern void rt_tsk_pass (void); +extern OS_TID rt_tsk_self (void); +extern OS_RESULT rt_tsk_prio (OS_TID task_id, U8 new_prio); +extern OS_TID rt_tsk_create (FUNCP task, U32 prio_stksz, void *stk, void *argv); +extern OS_RESULT rt_tsk_delete (OS_TID task_id); +#ifdef __CMSIS_RTOS +extern void rt_sys_init (void); +extern void rt_sys_start (void); +#else +extern void rt_sys_init (FUNCP first_task, U32 prio_stksz, void *stk); +#endif + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ + + + + + +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Time.c --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Time.c Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,94 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_TIME.C + * Purpose: Delay and interval wait functions + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +#include "rt_TypeDef.h" +#include "RTX_Config.h" +#include "rt_Task.h" +#include "rt_Time.h" + +/*---------------------------------------------------------------------------- + * Global Variables + *---------------------------------------------------------------------------*/ + +/* Free running system tick counter */ +U32 os_time; + + +/*---------------------------------------------------------------------------- + * Functions + *---------------------------------------------------------------------------*/ + + +/*--------------------------- rt_time_get -----------------------------------*/ + +U32 rt_time_get (void) { + /* Get system time tick */ + return (os_time); +} + + +/*--------------------------- rt_dly_wait -----------------------------------*/ + +void rt_dly_wait (U16 delay_time) { + /* Delay task by "delay_time" */ + rt_block (delay_time, WAIT_DLY); +} + + +/*--------------------------- rt_itv_set ------------------------------------*/ + +void rt_itv_set (U16 interval_time) { + /* Set interval length and define start of first interval */ + os_tsk.run->interval_time = interval_time; + os_tsk.run->delta_time = interval_time + (U16)os_time; +} + + +/*--------------------------- rt_itv_wait -----------------------------------*/ + +void rt_itv_wait (void) { + /* Wait for interval end and define start of next one */ + U16 delta; + + delta = os_tsk.run->delta_time - (U16)os_time; + os_tsk.run->delta_time += os_tsk.run->interval_time; + if ((delta & 0x8000) == 0) { + rt_block (delta, WAIT_ITV); + } +} + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Time.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Time.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,47 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_TIME.H + * Purpose: Delay and interval wait functions definitions + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Variables */ +extern U32 os_time; + +/* Functions */ +extern U32 rt_time_get (void); +extern void rt_dly_wait (U16 delay_time); +extern void rt_itv_set (U16 interval_time); +extern void rt_itv_wait (void); + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_Timer.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_Timer.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,46 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_TIMER.H + * Purpose: User timer functions + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Variables */ +extern struct OS_XTMR os_tmr; + +/* Functions */ +extern void rt_tmr_tick (void); +extern OS_ID rt_tmr_create (U16 tcnt, U16 info); +extern OS_ID rt_tmr_kill (OS_ID timer); + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-rtos/rtx/TARGET_CORTEX_A/rt_TypeDef.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos/rtx/TARGET_CORTEX_A/rt_TypeDef.h Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,167 @@ +/*---------------------------------------------------------------------------- + * RL-ARM - RTX + *---------------------------------------------------------------------------- + * Name: RT_TYPEDEF.H + * Purpose: Type Definitions + * Rev.: V4.60 + *---------------------------------------------------------------------------- + * + * Copyright (c) 1999-2009 KEIL, 2009-2012 ARM Germany GmbH + * All rights reserved. + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * - Neither the name of ARM nor the names of its contributors may be used + * to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *---------------------------------------------------------------------------*/ + +/* Types */ +typedef char S8; +typedef unsigned char U8; +typedef short S16; +typedef unsigned short U16; +typedef int S32; +typedef unsigned int U32; +typedef long long S64; +typedef unsigned long long U64; +typedef unsigned char BIT; +typedef unsigned int BOOL; +typedef void (*FUNCP)(void); + +typedef U32 OS_TID; +typedef void *OS_ID; +typedef U32 OS_RESULT; + +typedef struct OS_TCB { + /* General part: identical for all implementations. */ + U8 cb_type; /* Control Block Type */ + U8 state; /* Task state */ + U8 prio; /* Execution priority */ + U8 task_id; /* Task ID value for optimized TCB access */ + struct OS_TCB *p_lnk; /* Link pointer for ready/sem. wait list */ + struct OS_TCB *p_rlnk; /* Link pointer for sem./mbx lst backwards */ + struct OS_TCB *p_dlnk; /* Link pointer for delay list */ + struct OS_TCB *p_blnk; /* Link pointer for delay list backwards */ + U16 delta_time; /* Time until time out */ + U16 interval_time; /* Time interval for periodic waits */ + U16 events; /* Event flags */ + U16 waits; /* Wait flags */ + void **msg; /* Direct message passing when task waits */ + + /* Hardware dependant part: specific for Cortex processor */ + U8 stack_frame; /* Stack frame: 0x1 Basic/Extended, 0x2 FP stacked/not stacked */ + U8 reserved; + U16 priv_stack; /* Private stack size, 0= system assigned */ + U32 tsk_stack; /* Current task Stack pointer (R13) */ + U32 *stack; /* Pointer to Task Stack memory block */ + + /* Task entry point used for uVision debugger */ + FUNCP ptask; /* Task entry address */ +} *P_TCB; +#define TCB_TID 3 /* 'task id' offset */ +#define TCB_STACKF 32 /* 'stack_frame' offset */ +#define TCB_TSTACK 36 /* 'tsk_stack' offset */ + +typedef struct OS_PSFE { /* Post Service Fifo Entry */ + void *id; /* Object Identification */ + U32 arg; /* Object Argument */ +} *P_PSFE; + +typedef struct OS_PSQ { /* Post Service Queue */ + U8 first; /* FIFO Head Index */ + U8 last; /* FIFO Tail Index */ + U8 count; /* Number of stored items in FIFO */ + U8 size; /* FIFO Size */ + struct OS_PSFE q[1]; /* FIFO Content */ +} *P_PSQ; + +typedef struct OS_TSK { + P_TCB run; /* Current running task */ + P_TCB new; /* Scheduled task to run */ +} *P_TSK; + +typedef struct OS_ROBIN { /* Round Robin Control */ + P_TCB task; /* Round Robin task */ + U16 time; /* Round Robin switch time */ + U16 tout; /* Round Robin timeout */ +} *P_ROBIN; + +typedef struct OS_XCB { + U8 cb_type; /* Control Block Type */ + struct OS_TCB *p_lnk; /* Link pointer for ready/sem. wait list */ + struct OS_TCB *p_rlnk; /* Link pointer for sem./mbx lst backwards */ + struct OS_TCB *p_dlnk; /* Link pointer for delay list */ + struct OS_TCB *p_blnk; /* Link pointer for delay list backwards */ + U16 delta_time; /* Time until time out */ +} *P_XCB; + +typedef struct OS_MCB { + U8 cb_type; /* Control Block Type */ + U8 state; /* State flag variable */ + U8 isr_st; /* State flag variable for isr functions */ + struct OS_TCB *p_lnk; /* Chain of tasks waiting for message */ + U16 first; /* Index of the message list begin */ + U16 last; /* Index of the message list end */ + U16 count; /* Actual number of stored messages */ + U16 size; /* Maximum number of stored messages */ + void *msg[1]; /* FIFO for Message pointers 1st element */ +} *P_MCB; + +typedef struct OS_SCB { + U8 cb_type; /* Control Block Type */ + U8 mask; /* Semaphore token mask */ + U16 tokens; /* Semaphore tokens */ + struct OS_TCB *p_lnk; /* Chain of tasks waiting for tokens */ +} *P_SCB; + +typedef struct OS_MUCB { + U8 cb_type; /* Control Block Type */ + U8 prio; /* Owner task default priority */ + U16 level; /* Call nesting level */ + struct OS_TCB *p_lnk; /* Chain of tasks waiting for mutex */ + struct OS_TCB *owner; /* Mutex owner task */ +} *P_MUCB; + +typedef struct OS_XTMR { + struct OS_TMR *next; + U16 tcnt; +} *P_XTMR; + +typedef struct OS_TMR { + struct OS_TMR *next; /* Link pointer to Next timer */ + U16 tcnt; /* Timer delay count */ + U16 info; /* User defined call info */ +} *P_TMR; + +typedef struct OS_BM { + void *free; /* Pointer to first free memory block */ + void *end; /* Pointer to memory block end */ + U32 blk_size; /* Memory block size */ +} *P_BM; + +/* Definitions */ +#define __TRUE 1 +#define __FALSE 0 +#define NULL ((void *) 0) + +/*---------------------------------------------------------------------------- + * end of file + *---------------------------------------------------------------------------*/ +
diff -r eae1575da9ca -r 5d102be2566c mbed-src.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-src.lib Wed Oct 07 20:42:51 2015 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/mbed_official/code/mbed-src/#9c82b0f79f3d
diff -r eae1575da9ca -r 5d102be2566c mbed.bld --- a/mbed.bld Fri Mar 08 02:24:33 2013 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,1 +0,0 @@ -http://mbed.org/users/mbed_official/code/mbed/builds/3d0ef94e36ec \ No newline at end of file