Fix some dosctrings errors and trailing whitespaces

Signed-off-by: Kirill Luchikhin <kirill.luchikhin@intel.com>
This commit is contained in:
Kirill Luchikhin 2014-07-29 21:46:48 +04:00
parent 731704eaac
commit d15bf22536
21 changed files with 134 additions and 107 deletions

@ -49,7 +49,7 @@ class Buzzer {
/**
* Instanciates a Buzzer object
*
* @param pin Buzzer pin number
* @param pinNumber Buzzer pin number
*/
Buzzer (int pinNumber);

@ -73,7 +73,8 @@ class GY65 {
* Instanciates a GY65 object
*
* @param bus number of used bus
* @param devAddr addres of used i2c device
* @param devAddr address of used i2c device
* @param mode BMP085 mode
*/
GY65 (int bus, int devAddr, uint8_t mode = BMP085_ULTRAHIGHRES);

@ -29,19 +29,38 @@
namespace upm {
/**
* @brief C++ API for HMC5883l (3-axis digital compass)
*
* This file defines the HMC5883l C++ interface for libhmc5883l
*
* @snippet hmc5883l.cxx Interesting
*
*/
class Hmc5883l {
public:
/// Creates a Hmc5883l object
/**
* Creates a Hmc5883l object
*
* @param bus number of used i2c bus
*
*/
Hmc5883l(int bus);
/// Returns the direction
/*
* Returns the direction
*/
float direction();
/// Returns the heading
/*
* Returns the heading
*/
float heading();
/**
* Returns a pointer to an int[3] that contains the coordinates as ints
*
* @return *int to an int[3]
*/
int* coordinates();

@ -76,7 +76,7 @@ class I2CLcd {
public:
I2CLcd (int bus, int lcdAddress);
mraa_result_t write (int x, int y, std::string msg);
virtual mraa_result_t write (std::string msg) = 0;
virtual mraa_result_t setCursor (int row, int column) = 0;
virtual mraa_result_t clear () = 0;
@ -84,7 +84,7 @@ class I2CLcd {
virtual mraa_result_t i2Cmd (mraa_i2c_context ctx, uint8_t value);
virtual mraa_result_t i2cReg (mraa_i2c_context ctx, int deviceAdress, int addr, uint8_t data);
virtual mraa_result_t i2cData (mraa_i2c_context ctx, uint8_t value);
mraa_result_t close();
std::string name()
{

@ -52,7 +52,7 @@ Jhd1313m1::Jhd1313m1 (int bus, int lcdAddress, int rgbAddress) : I2CLcd(bus, lcd
i2Cmd (m_i2c_lcd_control, LCD_DISPLAYCONTROL | LCD_DISPLAYON);
clear ();
usleep(4500);
i2Cmd (m_i2c_lcd_control, LCD_ENTRYMODESET |
LCD_ENTRYLEFT |
LCD_ENTRYSHIFTDECREMENT);
@ -67,7 +67,7 @@ Jhd1313m1::Jhd1313m1 (int bus, int lcdAddress, int rgbAddress) : I2CLcd(bus, lcd
}
Jhd1313m1::~Jhd1313m1() {
}
mraa_result_t

@ -61,7 +61,7 @@ Lcm1602::Lcm1602(int bus_in, int addr_in) : I2CLcd (bus_in, addr_in) {
}
Lcm1602::~Lcm1602 () {
}
/*

@ -29,7 +29,7 @@
namespace upm {
#define DISPLAY_CMD_OFF 0xAE
#define DISPLAY_CMD_OFF 0xAE
#define DISPLAY_CMD_ON 0xAF
#define BASE_LOW_COLUMN_ADDR 0x00

@ -61,9 +61,9 @@ class Microphone {
* Get samples from microphone according to provided window and
* number of samples
*
* @return freqMS time between each sample (in microseconds)
* @return numberOfSamples number of sample to sample for this window
* @return buffer bufer with sampled data
* @param freqMS time between each sample (in microseconds)
* @param numberOfSamples number of sample to sample for this window
* @param buffer bufer with sampled data
*/
int getSampledWindow (unsigned int freqMS, unsigned int numberOfSamples, uint16_t * buffer);
@ -71,12 +71,19 @@ class Microphone {
* Given sampled buffer this method will return TRUE/FALSE if threshold
* was reached
*
* @return threshold sample threshold
* @return buffer buffer with samples
* @return len bufer len
* @param ctx threshold context
* @param threshold sample threshold
* @param buffer buffer with samples
* @param len bufer len
*/
int findThreshold (thresholdContext* ctx, unsigned int threshold, uint16_t * buffer, unsigned int len);
/**
*
* Print running average of threshold context
*
* @param ctx threshold context
*/
void printGraph (thresholdContext* ctx);
private:

@ -36,7 +36,7 @@ using namespace upm;
MMA7455::MMA7455 (int bus, int devAddr) {
unsigned char data = 0;
int nBytes = 0;
m_name = "MMA7455";
m_controlAddr = devAddr;
@ -49,7 +49,7 @@ MMA7455::MMA7455 (int bus, int devAddr) {
fprintf(stderr, "Messed up i2c bus\n");
return;
}
// setting GLVL 0x1 (64LSB/g) and MODE 0x1 (Measurement Mode)
data = (BIT (MMA7455_GLVL0) | BIT (MMA7455_MODE0));
error = ic2WriteReg (MMA7455_MCTL, &data, 0x1);
@ -57,7 +57,7 @@ MMA7455::MMA7455 (int bus, int devAddr) {
std::cout << "ERROR :: MMA7455 instance wan not created (Mode)" << std::endl;
return;
}
if (MRAA_SUCCESS != calibrate ()) {
std::cout << "ERROR :: MMA7455 instance wan not created (Calibrate)" << std::endl;
return;
@ -68,63 +68,63 @@ MMA7455::~MMA7455() {
mraa_i2c_stop(m_i2ControlCtx);
}
mraa_result_t
mraa_result_t
MMA7455::calibrate () {
mraa_result_t error = MRAA_SUCCESS;
int i = 0;
accelData xyz;
xyz.value.x = xyz.value.y = xyz.value.z = 0;
do {
error = readData (&xyz.value.x, &xyz.value.y, &xyz.value.z);
if (MRAA_SUCCESS != error) {
return error;
}
xyz.value.x += 2 * -xyz.value.x;
xyz.value.y += 2 * -xyz.value.y;
xyz.value.z += 2 * -(xyz.value.z - 64);
error = ic2WriteReg (MMA7455_XOFFL, (unsigned char *) &xyz, 0x6);
if (error != MRAA_SUCCESS) {
return error;
}
} while ( ++i < 3 );
return error;
}
mraa_result_t
mraa_result_t
MMA7455::readData (short * ptrX, short * ptrY, short * ptrZ) {
accelData xyz;
unsigned char data = 0;
int nBytes = 0;
/*do {
nBytes = ic2ReadReg (MMA7455_STATUS, &data, 0x1);
} while ( !(data & MMA7455_DRDY) && nBytes == MRAA_SUCCESS);
if (nBytes == MRAA_SUCCESS) {
std::cout << "NO_GDB :: 1" << std::endl;
return MRAA_SUCCESS;
}*/
nBytes = ic2ReadReg (MMA7455_XOUTL, (unsigned char *) &xyz, 0x6);
if (nBytes == 0) {
std::cout << "NO_GDB :: 2" << std::endl;
return MRAA_ERROR_UNSPECIFIED;
}
if (xyz.reg.x_msb & 0x02) {
xyz.reg.x_msb |= 0xFC;
}
if (xyz.reg.y_msb & 0x02) {
xyz.reg.y_msb |= 0xFC;
}
if (xyz.reg.z_msb & 0x02) {
xyz.reg.z_msb |= 0xFC;
}
@ -133,16 +133,16 @@ MMA7455::readData (short * ptrX, short * ptrY, short * ptrZ) {
*ptrX = xyz.value.x;
*ptrY = xyz.value.y;
*ptrZ = xyz.value.z;
return MRAA_SUCCESS;
}
int
int
MMA7455::ic2ReadReg (unsigned char reg, unsigned char * buf, unsigned char size) {
if (MRAA_SUCCESS != mraa_i2c_address(m_i2ControlCtx, m_controlAddr)) {
return 0;
}
if (MRAA_SUCCESS != mraa_i2c_write_byte(m_i2ControlCtx, reg)) {
return 0;
}
@ -150,11 +150,11 @@ MMA7455::ic2ReadReg (unsigned char reg, unsigned char * buf, unsigned char size)
if (MRAA_SUCCESS != mraa_i2c_address(m_i2ControlCtx, m_controlAddr)) {
return 0;
}
return (int) mraa_i2c_read(m_i2ControlCtx, buf, size);
}
mraa_result_t
mraa_result_t
MMA7455::ic2WriteReg (unsigned char reg, unsigned char * buf, unsigned char size) {
mraa_result_t error = MRAA_SUCCESS;
@ -173,4 +173,3 @@ MMA7455::ic2WriteReg (unsigned char reg, unsigned char * buf, unsigned char size
return error;
}

@ -53,7 +53,7 @@
#define MMA7455_YOFFH 0x13 // Read/Write, Offset Drift Y MSB
#define MMA7455_ZOFFL 0x14 // Read/Write, Offset Drift Z LSB
#define MMA7455_ZOFFH 0x15 // Read/Write, Offset Drift Z MSB
#define MMA7455_MCTL 0x16 // Read/Write, Mode Control Register
#define MMA7455_MCTL 0x16 // Read/Write, Mode Control Register
#define MMA7455_INTRST 0x17 // Read/Write, Interrupt Latch Reset
#define MMA7455_CTL1 0x18 // Read/Write, Control 1 Register
#define MMA7455_CTL2 0x19 // Read/Write, Control 2 Register
@ -64,11 +64,11 @@
#define MMA7455_TW 0x1E // Read/Write, Time Window for Second Pulse Value
#define MMA7455_RESERVED2 0x1F // Reserved
// Defines for the bits, to be able to change
// Defines for the bits, to be able to change
// between bit number and binary definition.
// By using the bit number, programming the MMA7455
// By using the bit number, programming the MMA7455
// is like programming an AVR microcontroller.
// But instead of using "(1<<X)", or "_BV(X)",
// But instead of using "(1<<X)", or "_BV(X)",
// the Arduino "bit(X)" is used.
#define MMA7455_D0 0
#define MMA7455_D1 1
@ -129,7 +129,7 @@
#define LOW 0
namespace upm {
union accelData {
struct {
unsigned char x_lsb;
@ -139,7 +139,7 @@ union accelData {
unsigned char z_lsb;
unsigned char z_msb;
} reg;
struct {
short x;
short y;
@ -179,12 +179,12 @@ class MMA7455 {
{
return m_name;
}
/**
* Calibrate the sensor
*/
mraa_result_t calibrate ();
/**
* Read X, Y and Z acceleration data
*
@ -193,21 +193,21 @@ class MMA7455 {
* @param ptrZ Z axis
*/
mraa_result_t readData (short * ptrX, short * ptrY, short * ptrZ);
/**
*
*
*
* @param reg register address
* @param buf register data buffer
* @param size buffer size
*/
int ic2ReadReg (unsigned char reg, unsigned char * buf, unsigned char size);
/**
*
*
*
* @param reg register address
* @param buf register data buffer
* @param buf register data buffer
* @param size buffer size
*/
mraa_result_t ic2WriteReg (unsigned char reg, unsigned char * buf, unsigned char size);

@ -46,7 +46,7 @@ MY9221::MY9221 (uint8_t di, uint8_t dcki) {
fprintf(stderr, "Are you sure that pin%d you requested is valid on your platform?", di);
exit(1);
}
// set direction (out)
error = mraa_gpio_dir(m_clkPinCtx, MRAA_GPIO_OUT);
if (error != MRAA_SUCCESS) {
@ -99,7 +99,7 @@ MY9221::lockData () {
mraa_result_t error = MRAA_SUCCESS;
error = mraa_gpio_write (m_dataPinCtx, LOW);
usleep(100);
for(int idx = 0; idx < 4; idx++) {
error = mraa_gpio_write (m_dataPinCtx, HIGH);
error = mraa_gpio_write (m_dataPinCtx, LOW);

@ -317,4 +317,3 @@ NRF24l01::nrfListenForChannel() {
dataRecievedHandler(); /* let know that data arrived */
}
}

@ -164,7 +164,7 @@ class NRF24l01 {
/**
* Send the buffer data
*
* @param *value pointer to the buffer
* @param value pointer to the buffer
*/
void nrfSend (uint8_t *value);
@ -226,7 +226,7 @@ class NRF24l01 {
/**
* Sink all arrived data into the provided buffer
*
* @param load size of the payload (MAX 32)
* @param data pointer to buffer of data
*/
void nrfGetData (uint8_t * data);
@ -238,7 +238,7 @@ class NRF24l01 {
/**
* Transmit provided data to the chip
*
* @param *dataout pointer to the buffer with data
* @param dataout pointer to the buffer with data
* @param len length of the buffer
*/
void nrfTransmitSync (uint8_t *dataout, uint8_t len);
@ -246,8 +246,8 @@ class NRF24l01 {
/**
* Recieve data from the chip
*
* @param *dataout pointer to the buffer with data
* @param *datain pointer to the buffer where the arrived data
* @param dataout pointer to the buffer with data
* @param datain pointer to the buffer where the arrived data
* will be sinked
* @param len length of the buffer
*/
@ -265,7 +265,7 @@ class NRF24l01 {
* Read continues data from register
*
* @param reg register address
* @param *value pointer to the buffer
* @param value pointer to the buffer
* @param len length of the buffer
*/
void nrfReadRegister (uint8_t reg, uint8_t * value, uint8_t len);
@ -274,7 +274,7 @@ class NRF24l01 {
* Write continues data to register
*
* @param reg register address
* @param *value pointer to the buffer
* @param value pointer to the buffer
* @param len length of the buffer
*/
void nrfWriteRegister (uint8_t reg, uint8_t * value, uint8_t len);

@ -28,9 +28,9 @@
void init_pulsensor (pulsensor_context * ctx, callback_handler handler) {
ctx->callback = handler;
ctx->pin_ctx = mraa_aio_init(0);
ctx->sample_counter = 0;
ctx->last_beat_time = 0;
ctx->threshold = 512;
@ -66,51 +66,51 @@ void * do_sample (void * arg) {
mraa_aio_context pin = ctx->pin_ctx;
data_from_sensor = mraa_aio_read (pin);
ctx->ret = FALSE;
ctx->sample_counter += 2;
int N = ctx->sample_counter - ctx->last_beat_time;
if (data_from_sensor < ctx->threshold && N > ( ctx->ibi / 5)* 3) {
if (data_from_sensor < ctx->trough) {
ctx->trough = data_from_sensor;
}
}
if (data_from_sensor > ctx->threshold && data_from_sensor > ctx->peak) {
ctx->peak = data_from_sensor;
}
if (N > 250) {
// printf ("(NO_GDB) DEBUG\n");
if ( (data_from_sensor > ctx->threshold) &&
(ctx->is_pulse == FALSE) &&
if ( (data_from_sensor > ctx->threshold) &&
(ctx->is_pulse == FALSE) &&
(N > (ctx->ibi / 5)* 3) ) {
ctx->is_pulse = callback_data.is_heart_beat = TRUE;
((pulsensor_context *) arg)->callback(callback_data);
ctx->ibi = ctx->sample_counter - ctx->last_beat_time;
ctx->last_beat_time = ctx->sample_counter;
// second beat
if (ctx->second_beat) {
ctx->second_beat = FALSE;
for (int i = 0; i <= 9; i++) {
ctx->ibi_rate[i] = ctx->ibi;
ctx->ibi_rate[i] = ctx->ibi;
}
}
// first beat
if (ctx->first_beat) {
ctx->first_beat = FALSE;
ctx->second_beat = TRUE;
ctx->ret = TRUE;
} else {
} else {
uint32_t running_total = 0;
for(int i = 0; i <= 8; i++){
ctx->ibi_rate[i] = ctx->ibi_rate[i+1];
running_total += ctx->ibi_rate[i];
}
ctx->ibi_rate[9] = ctx->ibi;
running_total += ctx->ibi_rate[9];
running_total /= 10;
@ -119,12 +119,12 @@ void * do_sample (void * arg) {
}
}
}
if (ctx->ret == FALSE) {
if (data_from_sensor < ctx->threshold && ctx->is_pulse == TRUE) {
ctx->is_pulse = callback_data.is_heart_beat = FALSE;
((pulsensor_context *) arg)->callback(callback_data);
ctx->is_pulse = FALSE;
ctx->apmlitude = ctx->peak - ctx->trough;
ctx->threshold = ctx->apmlitude / 2 + ctx->trough;
@ -136,12 +136,12 @@ void * do_sample (void * arg) {
ctx->threshold = 512;
ctx->peak = 512;
ctx->trough = 512;
ctx->last_beat_time = ctx->sample_counter;
ctx->last_beat_time = ctx->sample_counter;
ctx->first_beat = TRUE;
ctx->second_beat = FALSE;
}
}
usleep (2000);
}
}

@ -63,7 +63,7 @@ struct pulsensor_context {
uint8_t pin;
uint8_t ret;
mraa_aio_context pin_ctx;
callback_handler callback;
};

@ -41,9 +41,9 @@ Servo::Servo (int pin) {
m_maxAngle = 180.0;
m_servoPin = pin;
m_pwmServoContext = mraa_pwm_init (m_servoPin);
m_currAngle = 180;
setAngle (0);
}
@ -67,13 +67,13 @@ mraa_result_t Servo::setAngle (int angle) {
std::cout << "PWM context is NULL" << std::endl;
return MRAA_ERROR_UNSPECIFIED;
}
if (angle > m_maxAngle || angle < 0) {
return MRAA_ERROR_UNSPECIFIED;
}
int period = (m_maxPulseWidth - m_minPulseWidth) / m_maxAngle;
int cycles = (int)(100.0 * (abs (m_currAngle - angle) / m_maxAngle));
// int cycles = (int)(100.0 * ((float)angle / (float)m_maxAngle));
@ -86,7 +86,7 @@ mraa_result_t Servo::setAngle (int angle) {
mraa_pwm_enable (m_pwmServoContext, 0);
std::cout << "angle = " << angle << " ,pulse = " << calcPulseTraveling(angle) << ", cycles " << cycles << std::endl;
m_currAngle = angle;
}
@ -108,32 +108,32 @@ int Servo::calcPulseTraveling (int value) {
return (int) ((float)m_minPulseWidth + ((float)value / m_maxAngle) * ((float)m_maxPulseWidth - (float)m_minPulseWidth));
}
void
void
Servo::setMinPulseWidth (int width) {
m_minPulseWidth = width;
}
void
void
Servo::setMaxPulseWidth (int width) {
m_maxPulseWidth = width;
}
void
void
Servo::setMaxPeriod (int width) {
m_maxPeriod = width;
}
int
int
Servo::getMinPulseWidth () {
return m_minPulseWidth;
}
int
int
Servo::getMaxPulseWidth () {
return m_maxPulseWidth;
}
int
int
Servo::getMaxPeriod () {
return m_maxPeriod;
}

@ -79,43 +79,43 @@ class Servo {
{
return m_name;
}
/**
* Set min pulse width
*
* @param width HIGH signal width
*/
void setMinPulseWidth (int width);
/**
* Set max pulse width
*
* @param width HIGH signal width
*/
void setMaxPulseWidth (int width);
/**
* Set max period width
*
* @param width PWM period width
*/
void setMaxPeriod (int width);
/**
* Return min pulse width
*/
int getMinPulseWidth ();
/**
* Return max pulse width
*/
int getMaxPulseWidth ();
/**
* Return max PWM period width
*/
int getMaxPeriod ();
protected:
int calcPulseTraveling (int value);
@ -124,7 +124,7 @@ class Servo {
float m_maxAngle;
mraa_pwm_context m_pwmServoContext;
int m_currAngle;
int m_minPulseWidth;
int m_maxPulseWidth;
int m_maxPeriod;

@ -163,8 +163,10 @@ class GFX {
/**
* Draw a circle
*
* @param x center of circule on X scale
* @param y center of circule on Y scale
* @param x center of circle on X scale
* @param y center of circle on Y scale
* @param r radius of circle
* @param color color of circle
*/
void drawCircle (int16_t x, int16_t y, int16_t r, uint16_t color);

@ -552,7 +552,7 @@ class ST7735 : public GFX {
/**
* Execute set of commands and data
*
* @param *addr pointer to start of the commands/data section
* @param addr pointer to start of the commands/data section
*/
void executeCMDList (const uint8_t *addr);

@ -66,7 +66,7 @@ TM1637::TM1637 (uint8_t di, uint8_t dcki) {
fprintf(stderr, "Are you sure that pin%d you requested is valid on your platform?", di);
exit(1);
}
// set direction (out)
error = mraa_gpio_dir(m_clkPinCtx, MRAA_GPIO_IN);
if (error != MRAA_SUCCESS) {

@ -87,7 +87,7 @@ class TM1637 {
/**
* Set the the segment screen data and number of segments
*
* @param segments[] data to write on the segments, each elemnt
* @param segments data to write on the segments, each elemnt
* in array is segment
* @param length number of elements in segments array
* @param pos data writing offset