1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 04:15:44 +03:00

Cleanup line endings.

This commit is contained in:
Dominic Clifton 2014-07-31 23:53:34 +01:00
parent 2238f535be
commit 9f1a0fcb4c
47 changed files with 6212 additions and 6191 deletions

View file

@ -25,7 +25,8 @@
#define M_PI 3.14159265358979323846f
#endif /* M_PI */
#define RADX10 (M_PI / 1800.0f) // 0.001745329252f #define RAD (M_PI / 180.0f)
#define RADX10 (M_PI / 1800.0f) // 0.001745329252f
#define RAD (M_PI / 180.0f)
#define DEG2RAD(degrees) (degrees * RAD)

View file

@ -76,7 +76,8 @@ void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DCon
// use the last flash pages for storage
static uint32_t flashWriteAddress = (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG));
master_t masterConfig; // master config struct with data independent from profiles
master_t masterConfig; // master config struct with data independent from profiles
profile_t currentProfile; // profile config struct
static const uint8_t EEPROM_CONF_VERSION = 73;
@ -134,7 +135,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
#ifdef GPS
void resetGpsProfile(gpsProfile_t *gpsProfile)
{
{
gpsProfile->gps_wp_radius = 200;
gpsProfile->gps_lpf = 20;
gpsProfile->nav_slew_rate = 30;
@ -146,7 +147,7 @@ void resetGpsProfile(gpsProfile_t *gpsProfile)
#endif
void resetBarometerConfig(barometerConfig_t *barometerConfig)
{
{
barometerConfig->baro_sample_count = 21;
barometerConfig->baro_noise_lpf = 0.6f;
barometerConfig->baro_cf_vel = 0.985f;
@ -404,7 +405,7 @@ void activateConfig(void)
imuRuntimeConfig.gyro_cmpfm_factor = masterConfig.gyro_cmpfm_factor;
imuRuntimeConfig.acc_lpf_factor = currentProfile.acc_lpf_factor;
imuRuntimeConfig.acc_unarmedcal = currentProfile.acc_unarmedcal;;
imuRuntimeConfig.small_angle = masterConfig.small_angle;
configureImu(&imuRuntimeConfig, &currentProfile.pidProfile, &currentProfile.barometerConfig, &currentProfile.accDeadband);

View file

@ -1,84 +1,84 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
// System-wide
typedef struct master_t {
uint8_t version;
uint16_t size;
uint8_t magic_be; // magic number, should be 0xBE
uint8_t mixerConfiguration;
uint32_t enabledFeatures;
uint16_t looptime; // imu loop time in us
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
motorMixer_t customMixer[MAX_SUPPORTED_MOTORS]; // custom mixtable
// motor/esc/servo related stuff
escAndServoConfig_t escAndServoConfig;
flight3DConfig_t flight3DConfig;
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
// global sensor-related stuff
sensorAlignmentConfig_t sensorAlignmentConfig;
boardAlignment_t boardAlignment;
int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
uint16_t gyro_cmpf_factor; // Set the Gyro Weight for Gyro/Acc complementary filter. Increasing this value would reduce and delay Acc influence on the output of the filter.
uint16_t gyro_cmpfm_factor; // Set the Gyro Weight for Gyro/Magnetometer complementary filter. Increasing this value would reduce and delay Magnetometer influence on the output of the filter
gyroConfig_t gyroConfig;
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
flightDynamicsTrims_t accZero;
flightDynamicsTrims_t magZero;
batteryConfig_t batteryConfig;
rxConfig_t rxConfig;
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
uint8_t retarded_arm; // allow disarsm/arm on throttle down + roll left/right
uint8_t small_angle;
airplaneConfig_t airplaneConfig;
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
#ifdef GPS
gpsConfig_t gpsConfig;
#endif
serialConfig_t serialConfig;
telemetryConfig_t telemetryConfig;
profile_t profile[3]; // 3 separate profiles
uint8_t current_profile_index; // currently loaded profile
uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum
} master_t;
extern master_t masterConfig;
extern profile_t currentProfile;
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
// System-wide
typedef struct master_t {
uint8_t version;
uint16_t size;
uint8_t magic_be; // magic number, should be 0xBE
uint8_t mixerConfiguration;
uint32_t enabledFeatures;
uint16_t looptime; // imu loop time in us
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
motorMixer_t customMixer[MAX_SUPPORTED_MOTORS]; // custom mixtable
// motor/esc/servo related stuff
escAndServoConfig_t escAndServoConfig;
flight3DConfig_t flight3DConfig;
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
// global sensor-related stuff
sensorAlignmentConfig_t sensorAlignmentConfig;
boardAlignment_t boardAlignment;
int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
uint16_t gyro_cmpf_factor; // Set the Gyro Weight for Gyro/Acc complementary filter. Increasing this value would reduce and delay Acc influence on the output of the filter.
uint16_t gyro_cmpfm_factor; // Set the Gyro Weight for Gyro/Magnetometer complementary filter. Increasing this value would reduce and delay Magnetometer influence on the output of the filter
gyroConfig_t gyroConfig;
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
flightDynamicsTrims_t accZero;
flightDynamicsTrims_t magZero;
batteryConfig_t batteryConfig;
rxConfig_t rxConfig;
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
uint8_t retarded_arm; // allow disarsm/arm on throttle down + roll left/right
uint8_t small_angle;
airplaneConfig_t airplaneConfig;
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
#ifdef GPS
gpsConfig_t gpsConfig;
#endif
serialConfig_t serialConfig;
telemetryConfig_t telemetryConfig;
profile_t profile[3]; // 3 separate profiles
uint8_t current_profile_index; // currently loaded profile
uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum
} master_t;
extern master_t masterConfig;
extern profile_t currentProfile;

View file

@ -1,202 +1,202 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "common/maths.h"
#include "system.h"
#include "gpio.h"
#include "bus_spi.h"
#include "accgyro.h"
#include "accgyro_l3gd20.h"
extern int16_t debug[4];
#define READ_CMD ((uint8_t)0x80)
#define MULTIPLEBYTE_CMD ((uint8_t)0x40)
#define DUMMY_BYTE ((uint8_t)0x00)
#define CTRL_REG1_ADDR 0x20
#define CTRL_REG4_ADDR 0x23
#define CTRL_REG5_ADDR 0x24
#define OUT_TEMP_ADDR 0x26
#define OUT_X_L_ADDR 0x28
#define MODE_ACTIVE ((uint8_t)0x08)
#define OUTPUT_DATARATE_1 ((uint8_t)0x00)
#define OUTPUT_DATARATE_2 ((uint8_t)0x40)
#define OUTPUT_DATARATE_3 ((uint8_t)0x80)
#define OUTPUT_DATARATE_4 ((uint8_t)0xC0)
#define AXES_ENABLE ((uint8_t)0x07)
#define BANDWIDTH_1 ((uint8_t)0x00)
#define BANDWIDTH_2 ((uint8_t)0x10)
#define BANDWIDTH_3 ((uint8_t)0x20)
#define BANDWIDTH_4 ((uint8_t)0x30)
#define FULLSCALE_250 ((uint8_t)0x00)
#define FULLSCALE_500 ((uint8_t)0x10)
#define FULLSCALE_2000 ((uint8_t)0x20)
#define BLOCK_DATA_UPDATE_CONTINUOUS ((uint8_t)0x00)
#define BLE_MSB ((uint8_t)0x40)
#define BOOT ((uint8_t)0x80)
#define SPI1_GPIO GPIOA
#define SPI1_SCK_PIN GPIO_Pin_5
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource5
#define SPI1_SCK_CLK RCC_AHBPeriph_GPIOA
#define SPI1_MISO_PIN GPIO_Pin_6
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource6
#define SPI1_MISO_CLK RCC_AHBPeriph_GPIOA
#define SPI1_MOSI_PIN GPIO_Pin_7
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource7
#define SPI1_MOSI_CLK RCC_AHBPeriph_GPIOA
static void l3gd20SpiInit(SPI_TypeDef *SPIx)
{
GPIO_InitTypeDef GPIO_InitStructure;
SPI_InitTypeDef SPI_InitStructure;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE);
RCC_AHBPeriphClockCmd(SPI1_SCK_CLK | SPI1_MISO_CLK | SPI1_MOSI_CLK, ENABLE);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_SCK_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_MISO_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_MOSI_PIN_SOURCE, GPIO_AF_5);
// Init pins
GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN | SPI1_MISO_PIN | SPI1_MOSI_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
RCC_AHBPeriphClockCmd(L3GD20_CS_GPIO_CLK, ENABLE);
GPIO_InitStructure.GPIO_Pin = L3GD20_CS_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(L3GD20_CS_GPIO, &GPIO_InitStructure);
GPIO_SetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
SPI_I2S_DeInit(SPI1);
SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge;
SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4; // 36/4 = 9 MHz SPI Clock
SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
SPI_InitStructure.SPI_CRCPolynomial = 7;
SPI_Init(SPI1, &SPI_InitStructure);
SPI_RxFIFOThresholdConfig(L3GD20_SPI, SPI_RxFIFOThreshold_QF);
SPI_Cmd(SPI1, ENABLE);
}
void l3gd20GyroInit(void)
{
l3gd20SpiInit(L3GD20_SPI);
GPIO_ResetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
spiTransferByte(L3GD20_SPI, CTRL_REG5_ADDR);
spiTransferByte(L3GD20_SPI, BOOT);
GPIO_SetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
delayMicroseconds(100);
GPIO_ResetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
spiTransferByte(L3GD20_SPI, CTRL_REG1_ADDR);
spiTransferByte(L3GD20_SPI, MODE_ACTIVE | OUTPUT_DATARATE_3 | AXES_ENABLE | BANDWIDTH_3);
//spiTransferByte(L3GD20_SPI, MODE_ACTIVE | OUTPUT_DATARATE_4 | AXES_ENABLE | BANDWIDTH_4);
GPIO_SetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
delayMicroseconds(1);
GPIO_ResetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
spiTransferByte(L3GD20_SPI, CTRL_REG4_ADDR);
spiTransferByte(L3GD20_SPI, BLOCK_DATA_UPDATE_CONTINUOUS | BLE_MSB | FULLSCALE_2000);
GPIO_SetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
delay(100);
}
static void l3gd20GyroRead(int16_t *gyroData)
{
uint8_t buf[6];
GPIO_ResetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
spiTransferByte(L3GD20_SPI, OUT_X_L_ADDR | READ_CMD | MULTIPLEBYTE_CMD);
uint8_t index;
for (index = 0; index < sizeof(buf); index++) {
buf[index] = spiTransferByte(L3GD20_SPI, DUMMY_BYTE);
}
GPIO_SetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]);
gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]);
gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]);
#if 0
debug[0] = (int16_t)((buf[1] << 8) | buf[0]);
debug[1] = (int16_t)((buf[3] << 8) | buf[2]);
debug[2] = (int16_t)((buf[5] << 8) | buf[4]);
#endif
}
// Page 9 in datasheet, So - Sensitivity, Full Scale = 2000, 70 mdps/digit
#define L3GD20_GYRO_SCALE_FACTOR 0.07f
bool l3gd20Detect(gyro_t *gyro, uint16_t lpf)
{
gyro->init = l3gd20GyroInit;
gyro->read = l3gd20GyroRead;
gyro->scale = L3GD20_GYRO_SCALE_FACTOR;
return true; // blindly assume it's present, for now.
}
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "common/maths.h"
#include "system.h"
#include "gpio.h"
#include "bus_spi.h"
#include "accgyro.h"
#include "accgyro_l3gd20.h"
extern int16_t debug[4];
#define READ_CMD ((uint8_t)0x80)
#define MULTIPLEBYTE_CMD ((uint8_t)0x40)
#define DUMMY_BYTE ((uint8_t)0x00)
#define CTRL_REG1_ADDR 0x20
#define CTRL_REG4_ADDR 0x23
#define CTRL_REG5_ADDR 0x24
#define OUT_TEMP_ADDR 0x26
#define OUT_X_L_ADDR 0x28
#define MODE_ACTIVE ((uint8_t)0x08)
#define OUTPUT_DATARATE_1 ((uint8_t)0x00)
#define OUTPUT_DATARATE_2 ((uint8_t)0x40)
#define OUTPUT_DATARATE_3 ((uint8_t)0x80)
#define OUTPUT_DATARATE_4 ((uint8_t)0xC0)
#define AXES_ENABLE ((uint8_t)0x07)
#define BANDWIDTH_1 ((uint8_t)0x00)
#define BANDWIDTH_2 ((uint8_t)0x10)
#define BANDWIDTH_3 ((uint8_t)0x20)
#define BANDWIDTH_4 ((uint8_t)0x30)
#define FULLSCALE_250 ((uint8_t)0x00)
#define FULLSCALE_500 ((uint8_t)0x10)
#define FULLSCALE_2000 ((uint8_t)0x20)
#define BLOCK_DATA_UPDATE_CONTINUOUS ((uint8_t)0x00)
#define BLE_MSB ((uint8_t)0x40)
#define BOOT ((uint8_t)0x80)
#define SPI1_GPIO GPIOA
#define SPI1_SCK_PIN GPIO_Pin_5
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource5
#define SPI1_SCK_CLK RCC_AHBPeriph_GPIOA
#define SPI1_MISO_PIN GPIO_Pin_6
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource6
#define SPI1_MISO_CLK RCC_AHBPeriph_GPIOA
#define SPI1_MOSI_PIN GPIO_Pin_7
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource7
#define SPI1_MOSI_CLK RCC_AHBPeriph_GPIOA
static void l3gd20SpiInit(SPI_TypeDef *SPIx)
{
GPIO_InitTypeDef GPIO_InitStructure;
SPI_InitTypeDef SPI_InitStructure;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE);
RCC_AHBPeriphClockCmd(SPI1_SCK_CLK | SPI1_MISO_CLK | SPI1_MOSI_CLK, ENABLE);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_SCK_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_MISO_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_MOSI_PIN_SOURCE, GPIO_AF_5);
// Init pins
GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN | SPI1_MISO_PIN | SPI1_MOSI_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
RCC_AHBPeriphClockCmd(L3GD20_CS_GPIO_CLK, ENABLE);
GPIO_InitStructure.GPIO_Pin = L3GD20_CS_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(L3GD20_CS_GPIO, &GPIO_InitStructure);
GPIO_SetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
SPI_I2S_DeInit(SPI1);
SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge;
SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4; // 36/4 = 9 MHz SPI Clock
SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
SPI_InitStructure.SPI_CRCPolynomial = 7;
SPI_Init(SPI1, &SPI_InitStructure);
SPI_RxFIFOThresholdConfig(L3GD20_SPI, SPI_RxFIFOThreshold_QF);
SPI_Cmd(SPI1, ENABLE);
}
void l3gd20GyroInit(void)
{
l3gd20SpiInit(L3GD20_SPI);
GPIO_ResetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
spiTransferByte(L3GD20_SPI, CTRL_REG5_ADDR);
spiTransferByte(L3GD20_SPI, BOOT);
GPIO_SetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
delayMicroseconds(100);
GPIO_ResetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
spiTransferByte(L3GD20_SPI, CTRL_REG1_ADDR);
spiTransferByte(L3GD20_SPI, MODE_ACTIVE | OUTPUT_DATARATE_3 | AXES_ENABLE | BANDWIDTH_3);
//spiTransferByte(L3GD20_SPI, MODE_ACTIVE | OUTPUT_DATARATE_4 | AXES_ENABLE | BANDWIDTH_4);
GPIO_SetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
delayMicroseconds(1);
GPIO_ResetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
spiTransferByte(L3GD20_SPI, CTRL_REG4_ADDR);
spiTransferByte(L3GD20_SPI, BLOCK_DATA_UPDATE_CONTINUOUS | BLE_MSB | FULLSCALE_2000);
GPIO_SetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
delay(100);
}
static void l3gd20GyroRead(int16_t *gyroData)
{
uint8_t buf[6];
GPIO_ResetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
spiTransferByte(L3GD20_SPI, OUT_X_L_ADDR | READ_CMD | MULTIPLEBYTE_CMD);
uint8_t index;
for (index = 0; index < sizeof(buf); index++) {
buf[index] = spiTransferByte(L3GD20_SPI, DUMMY_BYTE);
}
GPIO_SetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]);
gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]);
gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]);
#if 0
debug[0] = (int16_t)((buf[1] << 8) | buf[0]);
debug[1] = (int16_t)((buf[3] << 8) | buf[2]);
debug[2] = (int16_t)((buf[5] << 8) | buf[4]);
#endif
}
// Page 9 in datasheet, So - Sensitivity, Full Scale = 2000, 70 mdps/digit
#define L3GD20_GYRO_SCALE_FACTOR 0.07f
bool l3gd20Detect(gyro_t *gyro, uint16_t lpf)
{
gyro->init = l3gd20GyroInit;
gyro->read = l3gd20GyroRead;
gyro->scale = L3GD20_GYRO_SCALE_FACTOR;
return true; // blindly assume it's present, for now.
}

View file

@ -1,26 +1,26 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define L3GD20_SPI SPI1
#define L3GD20_CS_GPIO GPIOE
#define L3GD20_CS_PIN GPIO_Pin_3
#define L3GD20_CS_GPIO_CLK RCC_AHBPeriph_GPIOE
bool l3gd20Detect(gyro_t *gyro, uint16_t lpf);
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define L3GD20_SPI SPI1
#define L3GD20_CS_GPIO GPIOE
#define L3GD20_CS_PIN GPIO_Pin_3
#define L3GD20_CS_GPIO_CLK RCC_AHBPeriph_GPIOE
bool l3gd20Detect(gyro_t *gyro, uint16_t lpf);

View file

@ -125,7 +125,7 @@ static void mpu3050Read(int16_t *gyroData)
uint8_t buf[6];
i2cRead(MPU3050_ADDRESS, MPU3050_GYRO_OUT, 6, buf);
gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]);
gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]);
gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]);

View file

@ -36,12 +36,25 @@
#define DMP_MEM_START_ADDR 0x6E
#define DMP_MEM_R_W 0x6F
#define MPU_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD #define MPU_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD #define MPU_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD #define MPU_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN #define MPU_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN #define MPU_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN #define MPU_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS #define MPU_RA_XA_OFFS_L_TC 0x07
#define MPU_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS #define MPU_RA_YA_OFFS_L_TC 0x09
#define MPU_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS #define MPU_RA_ZA_OFFS_L_TC 0x0B
#define MPU_RA_PRODUCT_ID 0x0C // Product ID Register #define MPU_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR #define MPU_RA_XG_OFFS_USRL 0x14
#define MPU_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR #define MPU_RA_YG_OFFS_USRL 0x16
#define MPU_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR #define MPU_RA_ZG_OFFS_USRL 0x18
#define MPU_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
#define MPU_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
#define MPU_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
#define MPU_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN
#define MPU_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN
#define MPU_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN
#define MPU_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS
#define MPU_RA_XA_OFFS_L_TC 0x07
#define MPU_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS
#define MPU_RA_YA_OFFS_L_TC 0x09
#define MPU_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS
#define MPU_RA_ZA_OFFS_L_TC 0x0B
#define MPU_RA_PRODUCT_ID 0x0C // Product ID Register
#define MPU_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR
#define MPU_RA_XG_OFFS_USRL 0x14
#define MPU_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR
#define MPU_RA_YG_OFFS_USRL 0x16
#define MPU_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR
#define MPU_RA_ZG_OFFS_USRL 0x18
#define MPU_RA_SMPLRT_DIV 0x19
#define MPU_RA_CONFIG 0x1A
#define MPU_RA_GYRO_CONFIG 0x1B
@ -112,7 +125,8 @@
#define MPU_RA_FIFO_R_W 0x74
#define MPU_RA_WHO_AM_I 0x75
#define MPU6050_SMPLRT_DIV 0 // 8000Hz
#define MPU6050_SMPLRT_DIV 0 // 8000Hz
#define MPU6050_LPF_256HZ 0
#define MPU6050_LPF_188HZ 1
#define MPU6050_LPF_98HZ 2
@ -296,7 +310,7 @@ static void mpu6050GyroRead(int16_t *gyroData)
uint8_t buf[6];
i2cRead(MPU6050_ADDRESS, MPU_RA_GYRO_XOUT_H, 6, buf);
gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]);
gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]);
gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]);

View file

@ -1,362 +1,362 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* Authors:
* Dominic Clifton - Cleanflight implementation
* John Ihlein - Initial FF32 code
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "common/axis.h"
#include "common/maths.h"
#include "system.h"
#include "gpio.h"
#include "bus_spi.h"
#include "accgyro.h"
#include "accgyro_spi_mpu6000.h"
// Registers
#define MPU6000_PRODUCT_ID 0x0C
#define MPU6000_SMPLRT_DIV 0x19
#define MPU6000_GYRO_CONFIG 0x1B
#define MPU6000_ACCEL_CONFIG 0x1C
#define MPU6000_FIFO_EN 0x23
#define MPU6000_INT_PIN_CFG 0x37
#define MPU6000_INT_ENABLE 0x38
#define MPU6000_INT_STATUS 0x3A
#define MPU6000_ACCEL_XOUT_H 0x3B
#define MPU6000_ACCEL_XOUT_L 0x3C
#define MPU6000_ACCEL_YOUT_H 0x3D
#define MPU6000_ACCEL_YOUT_L 0x3E
#define MPU6000_ACCEL_ZOUT_H 0x3F
#define MPU6000_ACCEL_ZOUT_L 0x40
#define MPU6000_TEMP_OUT_H 0x41
#define MPU6000_TEMP_OUT_L 0x42
#define MPU6000_GYRO_XOUT_H 0x43
#define MPU6000_GYRO_XOUT_L 0x44
#define MPU6000_GYRO_YOUT_H 0x45
#define MPU6000_GYRO_YOUT_L 0x46
#define MPU6000_GYRO_ZOUT_H 0x47
#define MPU6000_GYRO_ZOUT_L 0x48
#define MPU6000_USER_CTRL 0x6A
#define MPU6000_SIGNAL_PATH_RESET 0x68
#define MPU6000_PWR_MGMT_1 0x6B
#define MPU6000_PWR_MGMT_2 0x6C
#define MPU6000_FIFO_COUNTH 0x72
#define MPU6000_FIFO_COUNTL 0x73
#define MPU6000_FIFO_R_W 0x74
#define MPU6000_WHOAMI 0x75
// Bits
#define BIT_SLEEP 0x40
#define BIT_H_RESET 0x80
#define BITS_CLKSEL 0x07
#define MPU_CLK_SEL_PLLGYROX 0x01
#define MPU_CLK_SEL_PLLGYROZ 0x03
#define MPU_EXT_SYNC_GYROX 0x02
#define BITS_FS_250DPS 0x00
#define BITS_FS_500DPS 0x08
#define BITS_FS_1000DPS 0x10
#define BITS_FS_2000DPS 0x18
#define BITS_FS_2G 0x00
#define BITS_FS_4G 0x08
#define BITS_FS_8G 0x10
#define BITS_FS_16G 0x18
#define BITS_FS_MASK 0x18
#define BITS_DLPF_CFG_256HZ 0x00
#define BITS_DLPF_CFG_188HZ 0x01
#define BITS_DLPF_CFG_98HZ 0x02
#define BITS_DLPF_CFG_42HZ 0x03
#define BITS_DLPF_CFG_20HZ 0x04
#define BITS_DLPF_CFG_10HZ 0x05
#define BITS_DLPF_CFG_5HZ 0x06
#define BITS_DLPF_CFG_2100HZ_NOLPF 0x07
#define BITS_DLPF_CFG_MASK 0x07
#define BIT_INT_ANYRD_2CLEAR 0x10
#define BIT_RAW_RDY_EN 0x01
#define BIT_I2C_IF_DIS 0x10
#define BIT_INT_STATUS_DATA 0x01
#define BIT_GYRO 3
#define BIT_ACC 2
#define BIT_TEMP 1
// Product ID Description for MPU6000
// high 4 bits low 4 bits
// Product Name Product Revision
#define MPU6000ES_REV_C4 0x14
#define MPU6000ES_REV_C5 0x15
#define MPU6000ES_REV_D6 0x16
#define MPU6000ES_REV_D7 0x17
#define MPU6000ES_REV_D8 0x18
#define MPU6000_REV_C4 0x54
#define MPU6000_REV_C5 0x55
#define MPU6000_REV_D6 0x56
#define MPU6000_REV_D7 0x57
#define MPU6000_REV_D8 0x58
#define MPU6000_REV_D9 0x59
#define MPU6000_REV_D10 0x5A
#ifdef CC3D
#define MPU6000_CS_GPIO GPIOA
#define MPU6000_CS_PIN GPIO_Pin_4
#define MPU6000_SPI_INSTANCE SPI1
#endif
#define DISABLE_MPU6000 GPIO_SetBits(MPU6000_CS_GPIO, MPU6000_CS_PIN)
#define ENABLE_MPU6000 GPIO_ResetBits(MPU6000_CS_GPIO, MPU6000_CS_PIN)
void mpu6000SpiGyroRead(int16_t *gyroData);
void mpu6000SpiAccRead(int16_t *gyroData);
void mpu6000SpiGyroInit(void)
{
}
void mpu6000SpiAccInit(void)
{
acc_1G = 512 * 8;
}
bool mpu6000SpiDetect(void)
{
// FIXME this isn't working, not debugged yet.
return true; // just assume it's there for now
#if 0
uint8_t product;
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_PRODUCT_ID);
spiTransfer(MPU6000_SPI_INSTANCE, &product, NULL, 1);
DISABLE_MPU6000;
/* look for a product ID we recognise */
// verify product revision
switch (product) {
case MPU6000ES_REV_C4:
case MPU6000ES_REV_C5:
case MPU6000_REV_C4:
case MPU6000_REV_C5:
case MPU6000ES_REV_D6:
case MPU6000ES_REV_D7:
case MPU6000ES_REV_D8:
case MPU6000_REV_D6:
case MPU6000_REV_D7:
case MPU6000_REV_D8:
case MPU6000_REV_D9:
case MPU6000_REV_D10:
return true;
}
return false;
#endif
}
static bool initDone = false;
void mpu6000AccAndGyroInit() {
if (initDone) {
return;
}
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_PWR_MGMT_1); // Device Reset
spiTransferByte(MPU6000_SPI_INSTANCE, BIT_H_RESET);
DISABLE_MPU6000;
delay(150);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_SIGNAL_PATH_RESET); // Device Reset
spiTransferByte(MPU6000_SPI_INSTANCE, BIT_GYRO | BIT_ACC | BIT_TEMP);
DISABLE_MPU6000;
delay(150);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_PWR_MGMT_1); // Clock Source PPL with Z axis gyro reference
spiTransferByte(MPU6000_SPI_INSTANCE, MPU_CLK_SEL_PLLGYROZ);
DISABLE_MPU6000;
delayMicroseconds(1);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_USER_CTRL); // Disable Primary I2C Interface
spiTransferByte(MPU6000_SPI_INSTANCE, BIT_I2C_IF_DIS);
DISABLE_MPU6000;
delayMicroseconds(1);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_PWR_MGMT_2);
spiTransferByte(MPU6000_SPI_INSTANCE, 0x00);
DISABLE_MPU6000;
delayMicroseconds(1);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_SMPLRT_DIV); // Accel Sample Rate 1kHz
spiTransferByte(MPU6000_SPI_INSTANCE, 0x00); // Gyroscope Output Rate = 1kHz when the DLPF is enabled
DISABLE_MPU6000;
delayMicroseconds(1);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_ACCEL_CONFIG); // Accel +/- 8 G Full Scale
spiTransferByte(MPU6000_SPI_INSTANCE, BITS_FS_8G);
DISABLE_MPU6000;
delayMicroseconds(1);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_GYRO_CONFIG); // Gyro +/- 1000 DPS Full Scale
spiTransferByte(MPU6000_SPI_INSTANCE, BITS_FS_2000DPS);
DISABLE_MPU6000;
initDone = true;
}
bool mpu6000SpiAccDetect(acc_t *acc)
{
if (!mpu6000SpiDetect()) {
return false;
}
spiResetErrorCounter(MPU6000_SPI_INSTANCE);
mpu6000AccAndGyroInit();
acc->init = mpu6000SpiAccInit;
acc->read = mpu6000SpiAccRead;
delay(100);
return true;
}
bool mpu6000SpiGyroDetect(gyro_t *gyro, uint16_t lpf)
{
if (!mpu6000SpiDetect()) {
return false;
}
spiResetErrorCounter(MPU6000_SPI_INSTANCE);
mpu6000AccAndGyroInit();
uint8_t mpuLowPassFilter = BITS_DLPF_CFG_42HZ;
int16_t data[3];
// default lpf is 42Hz
switch (lpf) {
case 256:
mpuLowPassFilter = BITS_DLPF_CFG_256HZ;
break;
case 188:
mpuLowPassFilter = BITS_DLPF_CFG_188HZ;
break;
case 98:
mpuLowPassFilter = BITS_DLPF_CFG_98HZ;
break;
default:
case 42:
mpuLowPassFilter = BITS_DLPF_CFG_42HZ;
break;
case 20:
mpuLowPassFilter = BITS_DLPF_CFG_20HZ;
break;
case 10:
mpuLowPassFilter = BITS_DLPF_CFG_10HZ;
break;
case 5:
mpuLowPassFilter = BITS_DLPF_CFG_5HZ;
case 0:
mpuLowPassFilter = BITS_DLPF_CFG_2100HZ_NOLPF;
break;
}
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_CONFIG); // Accel and Gyro DLPF Setting
spiTransferByte(MPU6000_SPI_INSTANCE, mpuLowPassFilter);
DISABLE_MPU6000;
delayMicroseconds(1);
mpu6000SpiGyroRead(data);
if ((((int8_t)data[1]) == -1 && ((int8_t)data[0]) == -1) || spiGetErrorCounter(MPU6000_SPI_INSTANCE) != 0) {
spiResetErrorCounter(MPU6000_SPI_INSTANCE);
return false;
}
gyro->init = mpu6000SpiGyroInit;
gyro->read = mpu6000SpiGyroRead;
// 16.4 dps/lsb scalefactor
gyro->scale = 1.0f / 16.4f;
//gyro->scale = (4.0f / 16.4f) * (M_PI / 180.0f) * 0.000001f;
delay(100);
return true;
}
void mpu6000SpiGyroRead(int16_t *gyroData)
{
uint8_t buf[6];
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_GYRO_XOUT_H | 0x80);
spiTransfer(MPU6000_SPI_INSTANCE, buf, NULL, 6);
DISABLE_MPU6000;
gyroData[X] = (int16_t)((buf[0] << 8) | buf[1]);
gyroData[Y] = (int16_t)((buf[2] << 8) | buf[3]);
gyroData[Z] = (int16_t)((buf[4] << 8) | buf[5]);
}
void mpu6000SpiAccRead(int16_t *gyroData)
{
uint8_t buf[6];
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_ACCEL_XOUT_H | 0x80);
spiTransfer(MPU6000_SPI_INSTANCE, buf, NULL, 6);
DISABLE_MPU6000;
gyroData[X] = (int16_t)((buf[0] << 8) | buf[1]);
gyroData[Y] = (int16_t)((buf[2] << 8) | buf[3]);
gyroData[Z] = (int16_t)((buf[4] << 8) | buf[5]);
}
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* Authors:
* Dominic Clifton - Cleanflight implementation
* John Ihlein - Initial FF32 code
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "common/axis.h"
#include "common/maths.h"
#include "system.h"
#include "gpio.h"
#include "bus_spi.h"
#include "accgyro.h"
#include "accgyro_spi_mpu6000.h"
// Registers
#define MPU6000_PRODUCT_ID 0x0C
#define MPU6000_SMPLRT_DIV 0x19
#define MPU6000_GYRO_CONFIG 0x1B
#define MPU6000_ACCEL_CONFIG 0x1C
#define MPU6000_FIFO_EN 0x23
#define MPU6000_INT_PIN_CFG 0x37
#define MPU6000_INT_ENABLE 0x38
#define MPU6000_INT_STATUS 0x3A
#define MPU6000_ACCEL_XOUT_H 0x3B
#define MPU6000_ACCEL_XOUT_L 0x3C
#define MPU6000_ACCEL_YOUT_H 0x3D
#define MPU6000_ACCEL_YOUT_L 0x3E
#define MPU6000_ACCEL_ZOUT_H 0x3F
#define MPU6000_ACCEL_ZOUT_L 0x40
#define MPU6000_TEMP_OUT_H 0x41
#define MPU6000_TEMP_OUT_L 0x42
#define MPU6000_GYRO_XOUT_H 0x43
#define MPU6000_GYRO_XOUT_L 0x44
#define MPU6000_GYRO_YOUT_H 0x45
#define MPU6000_GYRO_YOUT_L 0x46
#define MPU6000_GYRO_ZOUT_H 0x47
#define MPU6000_GYRO_ZOUT_L 0x48
#define MPU6000_USER_CTRL 0x6A
#define MPU6000_SIGNAL_PATH_RESET 0x68
#define MPU6000_PWR_MGMT_1 0x6B
#define MPU6000_PWR_MGMT_2 0x6C
#define MPU6000_FIFO_COUNTH 0x72
#define MPU6000_FIFO_COUNTL 0x73
#define MPU6000_FIFO_R_W 0x74
#define MPU6000_WHOAMI 0x75
// Bits
#define BIT_SLEEP 0x40
#define BIT_H_RESET 0x80
#define BITS_CLKSEL 0x07
#define MPU_CLK_SEL_PLLGYROX 0x01
#define MPU_CLK_SEL_PLLGYROZ 0x03
#define MPU_EXT_SYNC_GYROX 0x02
#define BITS_FS_250DPS 0x00
#define BITS_FS_500DPS 0x08
#define BITS_FS_1000DPS 0x10
#define BITS_FS_2000DPS 0x18
#define BITS_FS_2G 0x00
#define BITS_FS_4G 0x08
#define BITS_FS_8G 0x10
#define BITS_FS_16G 0x18
#define BITS_FS_MASK 0x18
#define BITS_DLPF_CFG_256HZ 0x00
#define BITS_DLPF_CFG_188HZ 0x01
#define BITS_DLPF_CFG_98HZ 0x02
#define BITS_DLPF_CFG_42HZ 0x03
#define BITS_DLPF_CFG_20HZ 0x04
#define BITS_DLPF_CFG_10HZ 0x05
#define BITS_DLPF_CFG_5HZ 0x06
#define BITS_DLPF_CFG_2100HZ_NOLPF 0x07
#define BITS_DLPF_CFG_MASK 0x07
#define BIT_INT_ANYRD_2CLEAR 0x10
#define BIT_RAW_RDY_EN 0x01
#define BIT_I2C_IF_DIS 0x10
#define BIT_INT_STATUS_DATA 0x01
#define BIT_GYRO 3
#define BIT_ACC 2
#define BIT_TEMP 1
// Product ID Description for MPU6000
// high 4 bits low 4 bits
// Product Name Product Revision
#define MPU6000ES_REV_C4 0x14
#define MPU6000ES_REV_C5 0x15
#define MPU6000ES_REV_D6 0x16
#define MPU6000ES_REV_D7 0x17
#define MPU6000ES_REV_D8 0x18
#define MPU6000_REV_C4 0x54
#define MPU6000_REV_C5 0x55
#define MPU6000_REV_D6 0x56
#define MPU6000_REV_D7 0x57
#define MPU6000_REV_D8 0x58
#define MPU6000_REV_D9 0x59
#define MPU6000_REV_D10 0x5A
#ifdef CC3D
#define MPU6000_CS_GPIO GPIOA
#define MPU6000_CS_PIN GPIO_Pin_4
#define MPU6000_SPI_INSTANCE SPI1
#endif
#define DISABLE_MPU6000 GPIO_SetBits(MPU6000_CS_GPIO, MPU6000_CS_PIN)
#define ENABLE_MPU6000 GPIO_ResetBits(MPU6000_CS_GPIO, MPU6000_CS_PIN)
void mpu6000SpiGyroRead(int16_t *gyroData);
void mpu6000SpiAccRead(int16_t *gyroData);
void mpu6000SpiGyroInit(void)
{
}
void mpu6000SpiAccInit(void)
{
acc_1G = 512 * 8;
}
bool mpu6000SpiDetect(void)
{
// FIXME this isn't working, not debugged yet.
return true; // just assume it's there for now
#if 0
uint8_t product;
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_PRODUCT_ID);
spiTransfer(MPU6000_SPI_INSTANCE, &product, NULL, 1);
DISABLE_MPU6000;
/* look for a product ID we recognise */
// verify product revision
switch (product) {
case MPU6000ES_REV_C4:
case MPU6000ES_REV_C5:
case MPU6000_REV_C4:
case MPU6000_REV_C5:
case MPU6000ES_REV_D6:
case MPU6000ES_REV_D7:
case MPU6000ES_REV_D8:
case MPU6000_REV_D6:
case MPU6000_REV_D7:
case MPU6000_REV_D8:
case MPU6000_REV_D9:
case MPU6000_REV_D10:
return true;
}
return false;
#endif
}
static bool initDone = false;
void mpu6000AccAndGyroInit() {
if (initDone) {
return;
}
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_PWR_MGMT_1); // Device Reset
spiTransferByte(MPU6000_SPI_INSTANCE, BIT_H_RESET);
DISABLE_MPU6000;
delay(150);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_SIGNAL_PATH_RESET); // Device Reset
spiTransferByte(MPU6000_SPI_INSTANCE, BIT_GYRO | BIT_ACC | BIT_TEMP);
DISABLE_MPU6000;
delay(150);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_PWR_MGMT_1); // Clock Source PPL with Z axis gyro reference
spiTransferByte(MPU6000_SPI_INSTANCE, MPU_CLK_SEL_PLLGYROZ);
DISABLE_MPU6000;
delayMicroseconds(1);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_USER_CTRL); // Disable Primary I2C Interface
spiTransferByte(MPU6000_SPI_INSTANCE, BIT_I2C_IF_DIS);
DISABLE_MPU6000;
delayMicroseconds(1);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_PWR_MGMT_2);
spiTransferByte(MPU6000_SPI_INSTANCE, 0x00);
DISABLE_MPU6000;
delayMicroseconds(1);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_SMPLRT_DIV); // Accel Sample Rate 1kHz
spiTransferByte(MPU6000_SPI_INSTANCE, 0x00); // Gyroscope Output Rate = 1kHz when the DLPF is enabled
DISABLE_MPU6000;
delayMicroseconds(1);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_ACCEL_CONFIG); // Accel +/- 8 G Full Scale
spiTransferByte(MPU6000_SPI_INSTANCE, BITS_FS_8G);
DISABLE_MPU6000;
delayMicroseconds(1);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_GYRO_CONFIG); // Gyro +/- 1000 DPS Full Scale
spiTransferByte(MPU6000_SPI_INSTANCE, BITS_FS_2000DPS);
DISABLE_MPU6000;
initDone = true;
}
bool mpu6000SpiAccDetect(acc_t *acc)
{
if (!mpu6000SpiDetect()) {
return false;
}
spiResetErrorCounter(MPU6000_SPI_INSTANCE);
mpu6000AccAndGyroInit();
acc->init = mpu6000SpiAccInit;
acc->read = mpu6000SpiAccRead;
delay(100);
return true;
}
bool mpu6000SpiGyroDetect(gyro_t *gyro, uint16_t lpf)
{
if (!mpu6000SpiDetect()) {
return false;
}
spiResetErrorCounter(MPU6000_SPI_INSTANCE);
mpu6000AccAndGyroInit();
uint8_t mpuLowPassFilter = BITS_DLPF_CFG_42HZ;
int16_t data[3];
// default lpf is 42Hz
switch (lpf) {
case 256:
mpuLowPassFilter = BITS_DLPF_CFG_256HZ;
break;
case 188:
mpuLowPassFilter = BITS_DLPF_CFG_188HZ;
break;
case 98:
mpuLowPassFilter = BITS_DLPF_CFG_98HZ;
break;
default:
case 42:
mpuLowPassFilter = BITS_DLPF_CFG_42HZ;
break;
case 20:
mpuLowPassFilter = BITS_DLPF_CFG_20HZ;
break;
case 10:
mpuLowPassFilter = BITS_DLPF_CFG_10HZ;
break;
case 5:
mpuLowPassFilter = BITS_DLPF_CFG_5HZ;
case 0:
mpuLowPassFilter = BITS_DLPF_CFG_2100HZ_NOLPF;
break;
}
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_CONFIG); // Accel and Gyro DLPF Setting
spiTransferByte(MPU6000_SPI_INSTANCE, mpuLowPassFilter);
DISABLE_MPU6000;
delayMicroseconds(1);
mpu6000SpiGyroRead(data);
if ((((int8_t)data[1]) == -1 && ((int8_t)data[0]) == -1) || spiGetErrorCounter(MPU6000_SPI_INSTANCE) != 0) {
spiResetErrorCounter(MPU6000_SPI_INSTANCE);
return false;
}
gyro->init = mpu6000SpiGyroInit;
gyro->read = mpu6000SpiGyroRead;
// 16.4 dps/lsb scalefactor
gyro->scale = 1.0f / 16.4f;
//gyro->scale = (4.0f / 16.4f) * (M_PI / 180.0f) * 0.000001f;
delay(100);
return true;
}
void mpu6000SpiGyroRead(int16_t *gyroData)
{
uint8_t buf[6];
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_GYRO_XOUT_H | 0x80);
spiTransfer(MPU6000_SPI_INSTANCE, buf, NULL, 6);
DISABLE_MPU6000;
gyroData[X] = (int16_t)((buf[0] << 8) | buf[1]);
gyroData[Y] = (int16_t)((buf[2] << 8) | buf[3]);
gyroData[Z] = (int16_t)((buf[4] << 8) | buf[5]);
}
void mpu6000SpiAccRead(int16_t *gyroData)
{
uint8_t buf[6];
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock
ENABLE_MPU6000;
spiTransferByte(MPU6000_SPI_INSTANCE, MPU6000_ACCEL_XOUT_H | 0x80);
spiTransfer(MPU6000_SPI_INSTANCE, buf, NULL, 6);
DISABLE_MPU6000;
gyroData[X] = (int16_t)((buf[0] << 8) | buf[1]);
gyroData[Y] = (int16_t)((buf[2] << 8) | buf[3]);
gyroData[Z] = (int16_t)((buf[4] << 8) | buf[5]);
}

View file

@ -1,18 +1,18 @@
#pragma once
#define MPU6000_CONFIG 0x1A
#define BITS_DLPF_CFG_256HZ 0x00
#define BITS_DLPF_CFG_188HZ 0x01
#define BITS_DLPF_CFG_98HZ 0x02
#define BITS_DLPF_CFG_42HZ 0x03
#define GYRO_SCALE_FACTOR 0.00053292f // (4/131) * pi/180 (32.75 LSB = 1 DPS)
bool mpu6000SpiAccDetect(acc_t *acc);
bool mpu6000SpiGyroDetect(gyro_t *gyro, uint16_t lpf);
void mpu6000SpiGyroRead(int16_t *gyroData);
void mpu6000SpiAccRead(int16_t *gyroData);
#pragma once
#define MPU6000_CONFIG 0x1A
#define BITS_DLPF_CFG_256HZ 0x00
#define BITS_DLPF_CFG_188HZ 0x01
#define BITS_DLPF_CFG_98HZ 0x02
#define BITS_DLPF_CFG_42HZ 0x03
#define GYRO_SCALE_FACTOR 0.00053292f // (4/131) * pi/180 (32.75 LSB = 1 DPS)
bool mpu6000SpiAccDetect(acc_t *acc);
bool mpu6000SpiGyroDetect(gyro_t *gyro, uint16_t lpf);
void mpu6000SpiGyroRead(int16_t *gyroData);
void mpu6000SpiAccRead(int16_t *gyroData);

View file

@ -75,7 +75,9 @@ typedef struct {
#define E_SENSOR_NOT_DETECTED (char) 0
#define BMP085_PROM_START__ADDR 0xaa
#define BMP085_PROM_DATA__LEN 22
#define BMP085_T_MEASURE 0x2E // temperature measurent #define BMP085_P_MEASURE 0x34 // pressure measurement #define BMP085_CTRL_MEAS_REG 0xF4
#define BMP085_T_MEASURE 0x2E // temperature measurent
#define BMP085_P_MEASURE 0x34 // pressure measurement
#define BMP085_CTRL_MEAS_REG 0xF4
#define BMP085_ADC_OUT_MSB_REG 0xF6
#define BMP085_ADC_OUT_LSB_REG 0xF7
#define BMP085_CHIP_ID__POS 0
@ -96,7 +98,10 @@ typedef struct {
#define BMP085_GET_BITSLICE(regvar, bitname) (regvar & bitname##__MSK) >> bitname##__POS
#define BMP085_SET_BITSLICE(regvar, bitname, val) (regvar & ~bitname##__MSK) | ((val<<bitname##__POS)&bitname##__MSK)
#define SMD500_PARAM_MG 3038 //calibration parameter #define SMD500_PARAM_MH -7357 //calibration parameter #define SMD500_PARAM_MI 3791 //calibration parameter
#define SMD500_PARAM_MG 3038 //calibration parameter
#define SMD500_PARAM_MH -7357 //calibration parameter
#define SMD500_PARAM_MI 3791 //calibration parameter
static bmp085_t bmp085 = { { 0, } };
static bool bmp085InitDone = false;
static uint16_t bmp085_ut; // static result of temperature measurement

View file

@ -1,170 +1,170 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "gpio.h"
#include "timer.h"
#include "flight/failsafe.h" // FIXME dependency into the main code from a driver
#include "pwm_mapping.h"
#include "pwm_output.h"
typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors
typedef struct {
#ifdef STM32F303xC
volatile uint32_t *ccr;
#endif
#ifdef STM32F10X_MD
volatile uint16_t *ccr;
#endif
uint16_t period;
pwmWriteFuncPtr pwmWritePtr;
} pwmOutputPort_t;
static pwmOutputPort_t pwmOutputPorts[MAX_PWM_OUTPUT_PORTS];
static pwmOutputPort_t *motors[MAX_PWM_MOTORS];
static pwmOutputPort_t *servos[MAX_PWM_SERVOS];
#define PWM_BRUSHED_TIMER_MHZ 8
static uint8_t allocatedOutputPortCount = 0;
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value)
{
TIM_OCInitTypeDef TIM_OCInitStructure;
TIM_OCStructInit(&TIM_OCInitStructure);
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
TIM_OCInitStructure.TIM_Pulse = value;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
switch (channel) {
case TIM_Channel_1:
TIM_OC1Init(tim, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_2:
TIM_OC2Init(tim, &TIM_OCInitStructure);
TIM_OC2PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_3:
TIM_OC3Init(tim, &TIM_OCInitStructure);
TIM_OC3PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_4:
TIM_OC4Init(tim, &TIM_OCInitStructure);
TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable);
break;
}
}
static void pwmGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
{
gpio_config_t cfg;
cfg.pin = pin;
cfg.mode = mode;
cfg.speed = Speed_2MHz;
gpioInit(gpio, &cfg);
}
static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8_t mhz, uint16_t period, uint16_t value)
{
pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++];
configTimeBase(timerHardware->tim, period, mhz);
pwmGPIOConfig(timerHardware->gpio, timerHardware->pin, Mode_AF_PP);
pwmOCConfig(timerHardware->tim, timerHardware->channel, value);
if (timerHardware->outputEnable)
TIM_CtrlPWMOutputs(timerHardware->tim, ENABLE);
TIM_Cmd(timerHardware->tim, ENABLE);
switch (timerHardware->channel) {
case TIM_Channel_1:
p->ccr = &timerHardware->tim->CCR1;
break;
case TIM_Channel_2:
p->ccr = &timerHardware->tim->CCR2;
break;
case TIM_Channel_3:
p->ccr = &timerHardware->tim->CCR3;
break;
case TIM_Channel_4:
p->ccr = &timerHardware->tim->CCR4;
break;
}
p->period = period;
return p;
}
static void pwmWriteBrushed(uint8_t index, uint16_t value)
{
*motors[index]->ccr = (value - 1000) * motors[index]->period / 1000;
}
static void pwmWriteStandard(uint8_t index, uint16_t value)
{
*motors[index]->ccr = value;
}
void pwmWriteMotor(uint8_t index, uint16_t value)
{
if (motors[index] && index < MAX_MOTORS)
motors[index]->pwmWritePtr(index, value);
}
void pwmWriteServo(uint8_t index, uint16_t value)
{
if (servos[index] && index < MAX_SERVOS)
*servos[index]->ccr = value;
}
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
{
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, idlePulse);
motors[motorIndex]->pwmWritePtr = pwmWriteBrushed;
}
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
{
uint32_t hz = PWM_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, hz / motorPwmRate, idlePulse);
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
}
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse)
{
servos[servoIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, 1000000 / servoPwmRate, servoCenterPulse);
}
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "gpio.h"
#include "timer.h"
#include "flight/failsafe.h" // FIXME dependency into the main code from a driver
#include "pwm_mapping.h"
#include "pwm_output.h"
typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors
typedef struct {
#ifdef STM32F303xC
volatile uint32_t *ccr;
#endif
#ifdef STM32F10X_MD
volatile uint16_t *ccr;
#endif
uint16_t period;
pwmWriteFuncPtr pwmWritePtr;
} pwmOutputPort_t;
static pwmOutputPort_t pwmOutputPorts[MAX_PWM_OUTPUT_PORTS];
static pwmOutputPort_t *motors[MAX_PWM_MOTORS];
static pwmOutputPort_t *servos[MAX_PWM_SERVOS];
#define PWM_BRUSHED_TIMER_MHZ 8
static uint8_t allocatedOutputPortCount = 0;
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value)
{
TIM_OCInitTypeDef TIM_OCInitStructure;
TIM_OCStructInit(&TIM_OCInitStructure);
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
TIM_OCInitStructure.TIM_Pulse = value;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
switch (channel) {
case TIM_Channel_1:
TIM_OC1Init(tim, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_2:
TIM_OC2Init(tim, &TIM_OCInitStructure);
TIM_OC2PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_3:
TIM_OC3Init(tim, &TIM_OCInitStructure);
TIM_OC3PreloadConfig(tim, TIM_OCPreload_Enable);
break;
case TIM_Channel_4:
TIM_OC4Init(tim, &TIM_OCInitStructure);
TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable);
break;
}
}
static void pwmGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
{
gpio_config_t cfg;
cfg.pin = pin;
cfg.mode = mode;
cfg.speed = Speed_2MHz;
gpioInit(gpio, &cfg);
}
static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8_t mhz, uint16_t period, uint16_t value)
{
pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++];
configTimeBase(timerHardware->tim, period, mhz);
pwmGPIOConfig(timerHardware->gpio, timerHardware->pin, Mode_AF_PP);
pwmOCConfig(timerHardware->tim, timerHardware->channel, value);
if (timerHardware->outputEnable)
TIM_CtrlPWMOutputs(timerHardware->tim, ENABLE);
TIM_Cmd(timerHardware->tim, ENABLE);
switch (timerHardware->channel) {
case TIM_Channel_1:
p->ccr = &timerHardware->tim->CCR1;
break;
case TIM_Channel_2:
p->ccr = &timerHardware->tim->CCR2;
break;
case TIM_Channel_3:
p->ccr = &timerHardware->tim->CCR3;
break;
case TIM_Channel_4:
p->ccr = &timerHardware->tim->CCR4;
break;
}
p->period = period;
return p;
}
static void pwmWriteBrushed(uint8_t index, uint16_t value)
{
*motors[index]->ccr = (value - 1000) * motors[index]->period / 1000;
}
static void pwmWriteStandard(uint8_t index, uint16_t value)
{
*motors[index]->ccr = value;
}
void pwmWriteMotor(uint8_t index, uint16_t value)
{
if (motors[index] && index < MAX_MOTORS)
motors[index]->pwmWritePtr(index, value);
}
void pwmWriteServo(uint8_t index, uint16_t value)
{
if (servos[index] && index < MAX_SERVOS)
*servos[index]->ccr = value;
}
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
{
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, idlePulse);
motors[motorIndex]->pwmWritePtr = pwmWriteBrushed;
}
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
{
uint32_t hz = PWM_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, hz / motorPwmRate, idlePulse);
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
}
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse)
{
servos[servoIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, 1000000 / servoPwmRate, servoCenterPulse);
}

View file

@ -1,25 +1,25 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmWriteMotor(uint8_t index, uint16_t value);
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
void pwmWriteServo(uint8_t index, uint16_t value);
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmWriteMotor(uint8_t index, uint16_t value);
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
void pwmWriteServo(uint8_t index, uint16_t value);

View file

@ -1,112 +1,112 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include "platform.h"
#include "gpio.h"
#include "timer.h"
#include "pwm_mapping.h"
#include "pwm_rssi.h"
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity); // from pwm_output.c
typedef struct rssiInputPort_s {
uint8_t state;
captureCompare_t rise;
captureCompare_t fall;
captureCompare_t capture;
uint16_t raw;
const timerHardware_t *timerHardware;
} rssiInputPort_t;
static rssiInputPort_t rssiInputPort;
static void pwmRssiCallback(uint8_t reference, captureCompare_t capture)
{
const timerHardware_t *timerHardware = rssiInputPort.timerHardware;
if (rssiInputPort.state == 0) {
rssiInputPort.rise = capture;
rssiInputPort.state = 1;
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Falling);
} else {
rssiInputPort.fall = capture;
// compute and store capture
rssiInputPort.raw = rssiInputPort.fall - rssiInputPort.rise;
// switch state
rssiInputPort.state = 0;
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Rising);
}
}
static void pwmRSSIGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
{
gpio_config_t cfg;
cfg.pin = pin;
cfg.mode = mode;
cfg.speed = Speed_2MHz;
gpioInit(gpio, &cfg);
}
void pwmRSSIICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
{
TIM_ICInitTypeDef TIM_ICInitStructure;
TIM_ICStructInit(&TIM_ICInitStructure);
TIM_ICInitStructure.TIM_Channel = channel;
TIM_ICInitStructure.TIM_ICPolarity = polarity;
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
TIM_ICInitStructure.TIM_ICFilter = 0x00;
TIM_ICInit(tim, &TIM_ICInitStructure);
}
#define UNUSED_CALLBACK_REFERENCE 0
void pwmRSSIInConfig(uint8_t timerIndex)
{
const timerHardware_t *timerHardwarePtr = &(timerHardware[timerIndex]);
memset(&rssiInputPort, 0, sizeof(rssiInputPort));
rssiInputPort.timerHardware = timerHardwarePtr;
pwmRSSIGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode);
pwmRSSIICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
timerConfigure(timerHardwarePtr, 0xFFFF, 1);
configureTimerCaptureCompareInterrupt(timerHardwarePtr, UNUSED_CALLBACK_REFERENCE, pwmRssiCallback, NULL);
}
uint16_t pwmRSSIRead(void)
{
return rssiInputPort.raw;
}
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include "platform.h"
#include "gpio.h"
#include "timer.h"
#include "pwm_mapping.h"
#include "pwm_rssi.h"
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity); // from pwm_output.c
typedef struct rssiInputPort_s {
uint8_t state;
captureCompare_t rise;
captureCompare_t fall;
captureCompare_t capture;
uint16_t raw;
const timerHardware_t *timerHardware;
} rssiInputPort_t;
static rssiInputPort_t rssiInputPort;
static void pwmRssiCallback(uint8_t reference, captureCompare_t capture)
{
const timerHardware_t *timerHardware = rssiInputPort.timerHardware;
if (rssiInputPort.state == 0) {
rssiInputPort.rise = capture;
rssiInputPort.state = 1;
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Falling);
} else {
rssiInputPort.fall = capture;
// compute and store capture
rssiInputPort.raw = rssiInputPort.fall - rssiInputPort.rise;
// switch state
rssiInputPort.state = 0;
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Rising);
}
}
static void pwmRSSIGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
{
gpio_config_t cfg;
cfg.pin = pin;
cfg.mode = mode;
cfg.speed = Speed_2MHz;
gpioInit(gpio, &cfg);
}
void pwmRSSIICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
{
TIM_ICInitTypeDef TIM_ICInitStructure;
TIM_ICStructInit(&TIM_ICInitStructure);
TIM_ICInitStructure.TIM_Channel = channel;
TIM_ICInitStructure.TIM_ICPolarity = polarity;
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
TIM_ICInitStructure.TIM_ICFilter = 0x00;
TIM_ICInit(tim, &TIM_ICInitStructure);
}
#define UNUSED_CALLBACK_REFERENCE 0
void pwmRSSIInConfig(uint8_t timerIndex)
{
const timerHardware_t *timerHardwarePtr = &(timerHardware[timerIndex]);
memset(&rssiInputPort, 0, sizeof(rssiInputPort));
rssiInputPort.timerHardware = timerHardwarePtr;
pwmRSSIGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode);
pwmRSSIICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
timerConfigure(timerHardwarePtr, 0xFFFF, 1);
configureTimerCaptureCompareInterrupt(timerHardwarePtr, UNUSED_CALLBACK_REFERENCE, pwmRssiCallback, NULL);
}
uint16_t pwmRSSIRead(void)
{
return rssiInputPort.raw;
}

View file

@ -1,22 +1,22 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
uint16_t pwmRSSIRead(void);
void pwmRSSIInConfig(uint8_t timerIndex);
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
uint16_t pwmRSSIRead(void);
void pwmRSSIInConfig(uint8_t timerIndex);

View file

@ -1,305 +1,305 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "gpio.h"
#include "timer.h"
#include "pwm_mapping.h"
#include "pwm_rx.h"
#define PPM_CAPTURE_COUNT 12
#define PWM_INPUT_PORT_COUNT 8
#if PPM_CAPTURE_COUNT > MAX_PWM_INPUT_PORTS
#define PWM_PORTS_OR_PPM_CAPTURE_COUNT PPM_CAPTURE_COUNT
#else
#define PWM_PORTS_OR_PPM_CAPTURE_COUNT PWM_INPUT_PORT_COUNT
#endif
#define INPUT_FILTER_TO_HELP_WITH_NOISE_FROM_OPENLRS_TELEMETRY_RX 0x03
static inputFilteringMode_e inputFilteringMode;
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity);
typedef enum {
INPUT_MODE_PPM,
INPUT_MODE_PWM,
} pwmInputMode_t;
typedef struct {
pwmInputMode_t mode;
uint8_t channel; // only used for pwm, ignored by ppm
uint8_t state;
captureCompare_t rise;
captureCompare_t fall;
captureCompare_t capture;
const timerHardware_t *timerHardware;
} pwmInputPort_t;
static pwmInputPort_t pwmInputPorts[PWM_INPUT_PORT_COUNT];
static uint16_t captures[PWM_PORTS_OR_PPM_CAPTURE_COUNT];
#define PPM_TIMER_PERIOD 0xFFFF
#define PWM_TIMER_PERIOD 0xFFFF
static uint8_t ppmFrameCount = 0;
static uint8_t lastPPMFrameCount = 0;
typedef struct ppmDevice {
uint8_t pulseIndex;
uint32_t previousTime;
uint32_t currentTime;
uint32_t deltaTime;
uint32_t captures[PWM_PORTS_OR_PPM_CAPTURE_COUNT];
uint32_t largeCounter;
int8_t numChannels;
int8_t numChannelsPrevFrame;
uint8_t stableFramesSeenCount;
bool tracking;
} ppmDevice_t;
ppmDevice_t ppmDev;
#define PPM_IN_MIN_SYNC_PULSE_US 2700 // microseconds
#define PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds
#define PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds
#define PPM_STABLE_FRAMES_REQUIRED_COUNT 25
#define PPM_IN_MIN_NUM_CHANNELS 4
#define PPM_IN_MAX_NUM_CHANNELS PWM_PORTS_OR_PPM_CAPTURE_COUNT
#define PPM_RCVR_TIMEOUT 0
bool isPPMDataBeingReceived(void)
{
return (ppmFrameCount != lastPPMFrameCount);
}
void resetPPMDataReceivedState(void)
{
lastPPMFrameCount = ppmFrameCount;
}
#define MIN_CHANNELS_BEFORE_PPM_FRAME_CONSIDERED_VALID 4
void pwmRxInit(inputFilteringMode_e initialInputFilteringMode)
{
inputFilteringMode = initialInputFilteringMode;
}
static void ppmInit(void)
{
ppmDev.pulseIndex = 0;
ppmDev.previousTime = 0;
ppmDev.currentTime = 0;
ppmDev.deltaTime = 0;
ppmDev.largeCounter = 0;
ppmDev.numChannels = -1;
ppmDev.numChannelsPrevFrame = -1;
ppmDev.stableFramesSeenCount = 0;
ppmDev.tracking = false;
}
static void ppmOverflowCallback(uint8_t port, captureCompare_t capture)
{
ppmDev.largeCounter += capture;
}
static void ppmEdgeCallback(uint8_t port, captureCompare_t capture)
{
int32_t i;
/* Shift the last measurement out */
ppmDev.previousTime = ppmDev.currentTime;
/* Grab the new count */
ppmDev.currentTime = capture;
/* Convert to 32-bit timer result */
ppmDev.currentTime += ppmDev.largeCounter;
/* Capture computation */
ppmDev.deltaTime = ppmDev.currentTime - ppmDev.previousTime;
ppmDev.previousTime = ppmDev.currentTime;
#if 0
static uint32_t deltaTimes[20];
static uint8_t deltaIndex = 0;
deltaIndex = (deltaIndex + 1) % 20;
deltaTimes[deltaIndex] = ppmDev.deltaTime;
#endif
/* Sync pulse detection */
if (ppmDev.deltaTime > PPM_IN_MIN_SYNC_PULSE_US) {
if (ppmDev.pulseIndex == ppmDev.numChannelsPrevFrame
&& ppmDev.pulseIndex >= PPM_IN_MIN_NUM_CHANNELS
&& ppmDev.pulseIndex <= PPM_IN_MAX_NUM_CHANNELS) {
/* If we see n simultaneous frames of the same
number of channels we save it as our frame size */
if (ppmDev.stableFramesSeenCount < PPM_STABLE_FRAMES_REQUIRED_COUNT) {
ppmDev.stableFramesSeenCount++;
} else {
ppmDev.numChannels = ppmDev.pulseIndex;
}
} else {
ppmDev.stableFramesSeenCount = 0;
}
/* Check if the last frame was well formed */
if (ppmDev.pulseIndex == ppmDev.numChannels && ppmDev.tracking) {
/* The last frame was well formed */
for (i = 0; i < ppmDev.numChannels; i++) {
captures[i] = ppmDev.captures[i];
}
for (i = ppmDev.numChannels; i < PPM_IN_MAX_NUM_CHANNELS; i++) {
captures[i] = PPM_RCVR_TIMEOUT;
}
ppmFrameCount++;
}
ppmDev.tracking = true;
ppmDev.numChannelsPrevFrame = ppmDev.pulseIndex;
ppmDev.pulseIndex = 0;
/* We rely on the supervisor to set captureValue to invalid
if no valid frame is found otherwise we ride over it */
} else if (ppmDev.tracking) {
/* Valid pulse duration 0.75 to 2.5 ms*/
if (ppmDev.deltaTime > PPM_IN_MIN_CHANNEL_PULSE_US
&& ppmDev.deltaTime < PPM_IN_MAX_CHANNEL_PULSE_US
&& ppmDev.pulseIndex < PPM_IN_MAX_NUM_CHANNELS) {
ppmDev.captures[ppmDev.pulseIndex] = ppmDev.deltaTime;
ppmDev.pulseIndex++;
} else {
/* Not a valid pulse duration */
ppmDev.tracking = false;
for (i = 0; i < PWM_PORTS_OR_PPM_CAPTURE_COUNT; i++) {
ppmDev.captures[i] = PPM_RCVR_TIMEOUT;
}
}
}
}
static void pwmEdgeCallback(uint8_t port, captureCompare_t capture)
{
pwmInputPort_t *pwmInputPort = &pwmInputPorts[port];
const timerHardware_t *timerHardware = pwmInputPort->timerHardware;
if (pwmInputPort->state == 0) {
pwmInputPort->rise = capture;
pwmInputPort->state = 1;
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Falling);
} else {
pwmInputPort->fall = capture;
// compute and store capture
pwmInputPort->capture = pwmInputPort->fall - pwmInputPort->rise;
captures[pwmInputPort->channel] = pwmInputPort->capture;
// switch state
pwmInputPort->state = 0;
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Rising);
}
}
static void pwmGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
{
gpio_config_t cfg;
cfg.pin = pin;
cfg.mode = mode;
cfg.speed = Speed_2MHz;
gpioInit(gpio, &cfg);
}
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
{
TIM_ICInitTypeDef TIM_ICInitStructure;
TIM_ICStructInit(&TIM_ICInitStructure);
TIM_ICInitStructure.TIM_Channel = channel;
TIM_ICInitStructure.TIM_ICPolarity = polarity;
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
if (inputFilteringMode == INPUT_FILTERING_ENABLED) {
TIM_ICInitStructure.TIM_ICFilter = INPUT_FILTER_TO_HELP_WITH_NOISE_FROM_OPENLRS_TELEMETRY_RX;
} else {
TIM_ICInitStructure.TIM_ICFilter = 0x00;
}
TIM_ICInit(tim, &TIM_ICInitStructure);
}
void pwmInConfig(uint8_t timerIndex, uint8_t channel)
{
pwmInputPort_t *p = &pwmInputPorts[channel];
const timerHardware_t *timerHardwarePtr = &(timerHardware[timerIndex]);
p->channel = channel;
p->mode = INPUT_MODE_PWM;
p->timerHardware = timerHardwarePtr;
pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
timerConfigure(timerHardwarePtr, PWM_TIMER_PERIOD, PWM_TIMER_MHZ);
configureTimerCaptureCompareInterrupt(timerHardwarePtr, channel, pwmEdgeCallback, NULL);
}
#define UNUSED_PPM_TIMER_REFERENCE 0
#define FIRST_PWM_PORT 0
void ppmInConfig(uint8_t timerIndex)
{
ppmInit();
pwmInputPort_t *p = &pwmInputPorts[FIRST_PWM_PORT];
const timerHardware_t *timerHardwarePtr = &(timerHardware[timerIndex]);
p->mode = INPUT_MODE_PPM;
p->timerHardware = timerHardwarePtr;
pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
timerConfigure(timerHardwarePtr, PPM_TIMER_PERIOD, PWM_TIMER_MHZ);
configureTimerCaptureCompareInterrupt(timerHardwarePtr, UNUSED_PPM_TIMER_REFERENCE, ppmEdgeCallback, ppmOverflowCallback);
}
uint16_t pwmRead(uint8_t channel)
{
return captures[channel];
}
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "gpio.h"
#include "timer.h"
#include "pwm_mapping.h"
#include "pwm_rx.h"
#define PPM_CAPTURE_COUNT 12
#define PWM_INPUT_PORT_COUNT 8
#if PPM_CAPTURE_COUNT > MAX_PWM_INPUT_PORTS
#define PWM_PORTS_OR_PPM_CAPTURE_COUNT PPM_CAPTURE_COUNT
#else
#define PWM_PORTS_OR_PPM_CAPTURE_COUNT PWM_INPUT_PORT_COUNT
#endif
#define INPUT_FILTER_TO_HELP_WITH_NOISE_FROM_OPENLRS_TELEMETRY_RX 0x03
static inputFilteringMode_e inputFilteringMode;
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity);
typedef enum {
INPUT_MODE_PPM,
INPUT_MODE_PWM,
} pwmInputMode_t;
typedef struct {
pwmInputMode_t mode;
uint8_t channel; // only used for pwm, ignored by ppm
uint8_t state;
captureCompare_t rise;
captureCompare_t fall;
captureCompare_t capture;
const timerHardware_t *timerHardware;
} pwmInputPort_t;
static pwmInputPort_t pwmInputPorts[PWM_INPUT_PORT_COUNT];
static uint16_t captures[PWM_PORTS_OR_PPM_CAPTURE_COUNT];
#define PPM_TIMER_PERIOD 0xFFFF
#define PWM_TIMER_PERIOD 0xFFFF
static uint8_t ppmFrameCount = 0;
static uint8_t lastPPMFrameCount = 0;
typedef struct ppmDevice {
uint8_t pulseIndex;
uint32_t previousTime;
uint32_t currentTime;
uint32_t deltaTime;
uint32_t captures[PWM_PORTS_OR_PPM_CAPTURE_COUNT];
uint32_t largeCounter;
int8_t numChannels;
int8_t numChannelsPrevFrame;
uint8_t stableFramesSeenCount;
bool tracking;
} ppmDevice_t;
ppmDevice_t ppmDev;
#define PPM_IN_MIN_SYNC_PULSE_US 2700 // microseconds
#define PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds
#define PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds
#define PPM_STABLE_FRAMES_REQUIRED_COUNT 25
#define PPM_IN_MIN_NUM_CHANNELS 4
#define PPM_IN_MAX_NUM_CHANNELS PWM_PORTS_OR_PPM_CAPTURE_COUNT
#define PPM_RCVR_TIMEOUT 0
bool isPPMDataBeingReceived(void)
{
return (ppmFrameCount != lastPPMFrameCount);
}
void resetPPMDataReceivedState(void)
{
lastPPMFrameCount = ppmFrameCount;
}
#define MIN_CHANNELS_BEFORE_PPM_FRAME_CONSIDERED_VALID 4
void pwmRxInit(inputFilteringMode_e initialInputFilteringMode)
{
inputFilteringMode = initialInputFilteringMode;
}
static void ppmInit(void)
{
ppmDev.pulseIndex = 0;
ppmDev.previousTime = 0;
ppmDev.currentTime = 0;
ppmDev.deltaTime = 0;
ppmDev.largeCounter = 0;
ppmDev.numChannels = -1;
ppmDev.numChannelsPrevFrame = -1;
ppmDev.stableFramesSeenCount = 0;
ppmDev.tracking = false;
}
static void ppmOverflowCallback(uint8_t port, captureCompare_t capture)
{
ppmDev.largeCounter += capture;
}
static void ppmEdgeCallback(uint8_t port, captureCompare_t capture)
{
int32_t i;
/* Shift the last measurement out */
ppmDev.previousTime = ppmDev.currentTime;
/* Grab the new count */
ppmDev.currentTime = capture;
/* Convert to 32-bit timer result */
ppmDev.currentTime += ppmDev.largeCounter;
/* Capture computation */
ppmDev.deltaTime = ppmDev.currentTime - ppmDev.previousTime;
ppmDev.previousTime = ppmDev.currentTime;
#if 0
static uint32_t deltaTimes[20];
static uint8_t deltaIndex = 0;
deltaIndex = (deltaIndex + 1) % 20;
deltaTimes[deltaIndex] = ppmDev.deltaTime;
#endif
/* Sync pulse detection */
if (ppmDev.deltaTime > PPM_IN_MIN_SYNC_PULSE_US) {
if (ppmDev.pulseIndex == ppmDev.numChannelsPrevFrame
&& ppmDev.pulseIndex >= PPM_IN_MIN_NUM_CHANNELS
&& ppmDev.pulseIndex <= PPM_IN_MAX_NUM_CHANNELS) {
/* If we see n simultaneous frames of the same
number of channels we save it as our frame size */
if (ppmDev.stableFramesSeenCount < PPM_STABLE_FRAMES_REQUIRED_COUNT) {
ppmDev.stableFramesSeenCount++;
} else {
ppmDev.numChannels = ppmDev.pulseIndex;
}
} else {
ppmDev.stableFramesSeenCount = 0;
}
/* Check if the last frame was well formed */
if (ppmDev.pulseIndex == ppmDev.numChannels && ppmDev.tracking) {
/* The last frame was well formed */
for (i = 0; i < ppmDev.numChannels; i++) {
captures[i] = ppmDev.captures[i];
}
for (i = ppmDev.numChannels; i < PPM_IN_MAX_NUM_CHANNELS; i++) {
captures[i] = PPM_RCVR_TIMEOUT;
}
ppmFrameCount++;
}
ppmDev.tracking = true;
ppmDev.numChannelsPrevFrame = ppmDev.pulseIndex;
ppmDev.pulseIndex = 0;
/* We rely on the supervisor to set captureValue to invalid
if no valid frame is found otherwise we ride over it */
} else if (ppmDev.tracking) {
/* Valid pulse duration 0.75 to 2.5 ms*/
if (ppmDev.deltaTime > PPM_IN_MIN_CHANNEL_PULSE_US
&& ppmDev.deltaTime < PPM_IN_MAX_CHANNEL_PULSE_US
&& ppmDev.pulseIndex < PPM_IN_MAX_NUM_CHANNELS) {
ppmDev.captures[ppmDev.pulseIndex] = ppmDev.deltaTime;
ppmDev.pulseIndex++;
} else {
/* Not a valid pulse duration */
ppmDev.tracking = false;
for (i = 0; i < PWM_PORTS_OR_PPM_CAPTURE_COUNT; i++) {
ppmDev.captures[i] = PPM_RCVR_TIMEOUT;
}
}
}
}
static void pwmEdgeCallback(uint8_t port, captureCompare_t capture)
{
pwmInputPort_t *pwmInputPort = &pwmInputPorts[port];
const timerHardware_t *timerHardware = pwmInputPort->timerHardware;
if (pwmInputPort->state == 0) {
pwmInputPort->rise = capture;
pwmInputPort->state = 1;
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Falling);
} else {
pwmInputPort->fall = capture;
// compute and store capture
pwmInputPort->capture = pwmInputPort->fall - pwmInputPort->rise;
captures[pwmInputPort->channel] = pwmInputPort->capture;
// switch state
pwmInputPort->state = 0;
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Rising);
}
}
static void pwmGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
{
gpio_config_t cfg;
cfg.pin = pin;
cfg.mode = mode;
cfg.speed = Speed_2MHz;
gpioInit(gpio, &cfg);
}
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
{
TIM_ICInitTypeDef TIM_ICInitStructure;
TIM_ICStructInit(&TIM_ICInitStructure);
TIM_ICInitStructure.TIM_Channel = channel;
TIM_ICInitStructure.TIM_ICPolarity = polarity;
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
if (inputFilteringMode == INPUT_FILTERING_ENABLED) {
TIM_ICInitStructure.TIM_ICFilter = INPUT_FILTER_TO_HELP_WITH_NOISE_FROM_OPENLRS_TELEMETRY_RX;
} else {
TIM_ICInitStructure.TIM_ICFilter = 0x00;
}
TIM_ICInit(tim, &TIM_ICInitStructure);
}
void pwmInConfig(uint8_t timerIndex, uint8_t channel)
{
pwmInputPort_t *p = &pwmInputPorts[channel];
const timerHardware_t *timerHardwarePtr = &(timerHardware[timerIndex]);
p->channel = channel;
p->mode = INPUT_MODE_PWM;
p->timerHardware = timerHardwarePtr;
pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
timerConfigure(timerHardwarePtr, PWM_TIMER_PERIOD, PWM_TIMER_MHZ);
configureTimerCaptureCompareInterrupt(timerHardwarePtr, channel, pwmEdgeCallback, NULL);
}
#define UNUSED_PPM_TIMER_REFERENCE 0
#define FIRST_PWM_PORT 0
void ppmInConfig(uint8_t timerIndex)
{
ppmInit();
pwmInputPort_t *p = &pwmInputPorts[FIRST_PWM_PORT];
const timerHardware_t *timerHardwarePtr = &(timerHardware[timerIndex]);
p->mode = INPUT_MODE_PPM;
p->timerHardware = timerHardwarePtr;
pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
timerConfigure(timerHardwarePtr, PPM_TIMER_PERIOD, PWM_TIMER_MHZ);
configureTimerCaptureCompareInterrupt(timerHardwarePtr, UNUSED_PPM_TIMER_REFERENCE, ppmEdgeCallback, ppmOverflowCallback);
}
uint16_t pwmRead(uint8_t channel)
{
return captures[channel];
}

View file

@ -1,33 +1,33 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
typedef enum {
INPUT_FILTERING_DISABLED = 0,
INPUT_FILTERING_ENABLED
} inputFilteringMode_e;
void ppmInConfig(uint8_t timerIndex);
void pwmInConfig(uint8_t timerIndex, uint8_t channel);
uint16_t pwmRead(uint8_t channel);
bool isPPMDataBeingReceived(void);
void resetPPMDataReceivedState(void);
void pwmRxInit(inputFilteringMode_e initialInputFilteringMode);
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
typedef enum {
INPUT_FILTERING_DISABLED = 0,
INPUT_FILTERING_ENABLED
} inputFilteringMode_e;
void ppmInConfig(uint8_t timerIndex);
void pwmInConfig(uint8_t timerIndex, uint8_t channel);
uint16_t pwmRead(uint8_t channel);
bool isPPMDataBeingReceived(void);
void resetPPMDataReceivedState(void);
void pwmRxInit(inputFilteringMode_e initialInputFilteringMode);

View file

@ -1,104 +1,104 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "usb_core.h"
#include "usb_init.h"
#include "hw_config.h"
#include <stdbool.h>
#include <string.h>
#include "drivers/system.h"
#include "serial.h"
#include "serial_usb_vcp.h"
#define USB_TIMEOUT 50
static vcpPort_t vcpPort;
void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate)
{
// TODO implement
}
void usbVcpSetMode(serialPort_t *instance, portMode_t mode)
{
// TODO implement
}
bool isUsbVcpTransmitBufferEmpty(serialPort_t *instance)
{
return true;
}
uint8_t usbVcpAvailable(serialPort_t *instance)
{
return receiveLength & 0xFF; // FIXME use uint32_t return type everywhere
}
uint8_t usbVcpRead(serialPort_t *instance)
{
uint8_t buf[1];
uint32_t rxed = 0;
while (rxed < 1) {
rxed += CDC_Receive_DATA((uint8_t*)buf + rxed, 1 - rxed);
}
return buf[0];
}
void usbVcpWrite(serialPort_t *instance, uint8_t c)
{
uint32_t txed;
uint32_t start = millis();
if (!(usbIsConnected() && usbIsConfigured())) {
return;
}
do {
txed = CDC_Send_DATA((uint8_t*)&c, 1);
} while (txed < 1 && (millis() - start < USB_TIMEOUT));
}
const struct serialPortVTable usbVTable[] = { { usbVcpWrite, usbVcpAvailable, usbVcpRead, usbVcpSetBaudRate, isUsbVcpTransmitBufferEmpty, usbVcpSetMode } };
serialPort_t *usbVcpOpen(void)
{
vcpPort_t *s;
Set_System();
Set_USBClock();
USB_Interrupts_Config();
USB_Init();
s = &vcpPort;
s->port.vTable = usbVTable;
return (serialPort_t *)s;
}
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "usb_core.h"
#include "usb_init.h"
#include "hw_config.h"
#include <stdbool.h>
#include <string.h>
#include "drivers/system.h"
#include "serial.h"
#include "serial_usb_vcp.h"
#define USB_TIMEOUT 50
static vcpPort_t vcpPort;
void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate)
{
// TODO implement
}
void usbVcpSetMode(serialPort_t *instance, portMode_t mode)
{
// TODO implement
}
bool isUsbVcpTransmitBufferEmpty(serialPort_t *instance)
{
return true;
}
uint8_t usbVcpAvailable(serialPort_t *instance)
{
return receiveLength & 0xFF; // FIXME use uint32_t return type everywhere
}
uint8_t usbVcpRead(serialPort_t *instance)
{
uint8_t buf[1];
uint32_t rxed = 0;
while (rxed < 1) {
rxed += CDC_Receive_DATA((uint8_t*)buf + rxed, 1 - rxed);
}
return buf[0];
}
void usbVcpWrite(serialPort_t *instance, uint8_t c)
{
uint32_t txed;
uint32_t start = millis();
if (!(usbIsConnected() && usbIsConfigured())) {
return;
}
do {
txed = CDC_Send_DATA((uint8_t*)&c, 1);
} while (txed < 1 && (millis() - start < USB_TIMEOUT));
}
const struct serialPortVTable usbVTable[] = { { usbVcpWrite, usbVcpAvailable, usbVcpRead, usbVcpSetBaudRate, isUsbVcpTransmitBufferEmpty, usbVcpSetMode } };
serialPort_t *usbVcpOpen(void)
{
vcpPort_t *s;
Set_System();
Set_USBClock();
USB_Interrupts_Config();
USB_Init();
s = &vcpPort;
s->port.vTable = usbVTable;
return (serialPort_t *)s;
}

View file

@ -1,34 +1,34 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "serial.h"
typedef struct {
serialPort_t port;
} vcpPort_t;
serialPort_t *usbVcpOpen(void);
uint8_t usbVcpAvailable(serialPort_t *instance);
uint8_t usbVcpRead(serialPort_t *instance);
void usbVcpWrite(serialPort_t *instance, uint8_t ch);
void usbPrintStr(const char *str);
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "serial.h"
typedef struct {
serialPort_t port;
} vcpPort_t;
serialPort_t *usbVcpOpen(void);
uint8_t usbVcpAvailable(serialPort_t *instance);
uint8_t usbVcpRead(serialPort_t *instance);
void usbVcpWrite(serialPort_t *instance, uint8_t ch);
void usbPrintStr(const char *str);

View file

@ -1,155 +1,155 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "system.h"
#include "gpio.h"
#include "sonar_hcsr04.h"
#ifdef SONAR
/* HC-SR04 consists of ultrasonic transmitter, receiver, and control circuits.
* When trigged it sends out a series of 40KHz ultrasonic pulses and receives
* echo froman object. The distance between the unit and the object is calculated
* by measuring the traveling time of sound and output it as the width of a TTL pulse.
*
* *** Warning: HC-SR04 operates at +5V ***
*
*/
static uint16_t trigger_pin;
static uint16_t echo_pin;
static uint32_t exti_line;
static uint8_t exti_pin_source;
static IRQn_Type exti_irqn;
static uint32_t last_measurement;
static volatile int32_t *distance_ptr;
void ECHO_EXTI_IRQHandler(void)
{
static uint32_t timing_start;
uint32_t timing_stop;
if (digitalIn(GPIOB, echo_pin) != 0) {
timing_start = micros();
} else {
timing_stop = micros();
if (timing_stop > timing_start) {
// The speed of sound is 340 m/s or approx. 29 microseconds per centimeter.
// The ping travels out and back, so to find the distance of the
// object we take half of the distance traveled.
//
// 340 m/s = 0.034 cm/microsecond = 29.41176471 *2 = 58.82352941 rounded to 59
int32_t distance = (timing_stop - timing_start) / 59;
// this sonar range is up to 4meter , but 3meter is the safe working range (+tilted and roll)
if (distance > 300)
distance = -1;
*distance_ptr = distance;
}
}
EXTI_ClearITPendingBit(exti_line);
}
void EXTI1_IRQHandler(void)
{
ECHO_EXTI_IRQHandler();
}
void EXTI9_5_IRQHandler(void)
{
ECHO_EXTI_IRQHandler();
}
void hcsr04_init(sonar_config_t config)
{
gpio_config_t gpio;
EXTI_InitTypeDef EXTIInit;
// enable AFIO for EXTI support - already done is drv_system.c
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph, ENABLE);
switch (config) {
case sonar_pwm56:
trigger_pin = Pin_8; // PWM5 (PB8) - 5v tolerant
echo_pin = Pin_9; // PWM6 (PB9) - 5v tolerant
exti_line = EXTI_Line9;
exti_pin_source = GPIO_PinSource9;
exti_irqn = EXTI9_5_IRQn;
break;
case sonar_rc78:
trigger_pin = Pin_0; // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
echo_pin = Pin_1; // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
exti_line = EXTI_Line1;
exti_pin_source = GPIO_PinSource1;
exti_irqn = EXTI1_IRQn;
break;
}
// tp - trigger pin
gpio.pin = trigger_pin;
gpio.mode = Mode_Out_PP;
gpio.speed = Speed_2MHz;
gpioInit(GPIOB, &gpio);
// ep - echo pin
gpio.pin = echo_pin;
gpio.mode = Mode_IN_FLOATING;
gpioInit(GPIOB, &gpio);
// setup external interrupt on echo pin
gpioExtiLineConfig(GPIO_PortSourceGPIOB, exti_pin_source);
EXTI_ClearITPendingBit(exti_line);
EXTIInit.EXTI_Line = exti_line;
EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt;
EXTIInit.EXTI_Trigger = EXTI_Trigger_Rising_Falling;
EXTIInit.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTIInit);
NVIC_EnableIRQ(exti_irqn);
last_measurement = millis() - 60; // force 1st measurement in hcsr04_get_distance()
}
// distance calculation is done asynchronously, using interrupt
void hcsr04_get_distance(volatile int32_t *distance)
{
uint32_t current_time = millis();
if (current_time < (last_measurement + 60)) {
// the repeat interval of trig signal should be greater than 60ms
// to avoid interference between connective measurements.
return;
}
last_measurement = current_time;
distance_ptr = distance;
digitalHi(GPIOB, trigger_pin);
// The width of trig signal must be greater than 10us
delayMicroseconds(11);
digitalLo(GPIOB, trigger_pin);
}
#endif
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "system.h"
#include "gpio.h"
#include "sonar_hcsr04.h"
#ifdef SONAR
/* HC-SR04 consists of ultrasonic transmitter, receiver, and control circuits.
* When trigged it sends out a series of 40KHz ultrasonic pulses and receives
* echo froman object. The distance between the unit and the object is calculated
* by measuring the traveling time of sound and output it as the width of a TTL pulse.
*
* *** Warning: HC-SR04 operates at +5V ***
*
*/
static uint16_t trigger_pin;
static uint16_t echo_pin;
static uint32_t exti_line;
static uint8_t exti_pin_source;
static IRQn_Type exti_irqn;
static uint32_t last_measurement;
static volatile int32_t *distance_ptr;
void ECHO_EXTI_IRQHandler(void)
{
static uint32_t timing_start;
uint32_t timing_stop;
if (digitalIn(GPIOB, echo_pin) != 0) {
timing_start = micros();
} else {
timing_stop = micros();
if (timing_stop > timing_start) {
// The speed of sound is 340 m/s or approx. 29 microseconds per centimeter.
// The ping travels out and back, so to find the distance of the
// object we take half of the distance traveled.
//
// 340 m/s = 0.034 cm/microsecond = 29.41176471 *2 = 58.82352941 rounded to 59
int32_t distance = (timing_stop - timing_start) / 59;
// this sonar range is up to 4meter , but 3meter is the safe working range (+tilted and roll)
if (distance > 300)
distance = -1;
*distance_ptr = distance;
}
}
EXTI_ClearITPendingBit(exti_line);
}
void EXTI1_IRQHandler(void)
{
ECHO_EXTI_IRQHandler();
}
void EXTI9_5_IRQHandler(void)
{
ECHO_EXTI_IRQHandler();
}
void hcsr04_init(sonar_config_t config)
{
gpio_config_t gpio;
EXTI_InitTypeDef EXTIInit;
// enable AFIO for EXTI support - already done is drv_system.c
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph, ENABLE);
switch (config) {
case sonar_pwm56:
trigger_pin = Pin_8; // PWM5 (PB8) - 5v tolerant
echo_pin = Pin_9; // PWM6 (PB9) - 5v tolerant
exti_line = EXTI_Line9;
exti_pin_source = GPIO_PinSource9;
exti_irqn = EXTI9_5_IRQn;
break;
case sonar_rc78:
trigger_pin = Pin_0; // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
echo_pin = Pin_1; // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
exti_line = EXTI_Line1;
exti_pin_source = GPIO_PinSource1;
exti_irqn = EXTI1_IRQn;
break;
}
// tp - trigger pin
gpio.pin = trigger_pin;
gpio.mode = Mode_Out_PP;
gpio.speed = Speed_2MHz;
gpioInit(GPIOB, &gpio);
// ep - echo pin
gpio.pin = echo_pin;
gpio.mode = Mode_IN_FLOATING;
gpioInit(GPIOB, &gpio);
// setup external interrupt on echo pin
gpioExtiLineConfig(GPIO_PortSourceGPIOB, exti_pin_source);
EXTI_ClearITPendingBit(exti_line);
EXTIInit.EXTI_Line = exti_line;
EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt;
EXTIInit.EXTI_Trigger = EXTI_Trigger_Rising_Falling;
EXTIInit.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTIInit);
NVIC_EnableIRQ(exti_irqn);
last_measurement = millis() - 60; // force 1st measurement in hcsr04_get_distance()
}
// distance calculation is done asynchronously, using interrupt
void hcsr04_get_distance(volatile int32_t *distance)
{
uint32_t current_time = millis();
if (current_time < (last_measurement + 60)) {
// the repeat interval of trig signal should be greater than 60ms
// to avoid interference between connective measurements.
return;
}
last_measurement = current_time;
distance_ptr = distance;
digitalHi(GPIOB, trigger_pin);
// The width of trig signal must be greater than 10us
delayMicroseconds(11);
digitalLo(GPIOB, trigger_pin);
}
#endif

View file

@ -117,7 +117,7 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control
// it's the ANGLE mode - control is angle based, so control loop is needed
AngleRate = errorAngle * pidProfile->A_level;
} else {
//control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
//control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
AngleRate = (float)((controlRateConfig->rollPitchRate + 20) * rcCommand[axis]) / 50.0f; // 200dps to 1200dps max yaw rate
if (f.HORIZON_MODE) {
// mix up angle error to desired AngleRate to add a little auto-level feel
@ -189,7 +189,7 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
if (shouldAutotune()) {
errorAngle = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(errorAngle)));
}
PTermACC = errorAngle * pidProfile->P8[PIDLEVEL] / 100; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result
PTermACC = constrain(PTermACC, -pidProfile->D8[PIDLEVEL] * 5, +pidProfile->D8[PIDLEVEL] * 5);

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

View file

@ -652,7 +652,7 @@ static void evaluateCommand(void)
if(masterConfig.batteryConfig.multiwiiCurrentMeterOutput) {
serialize16((uint16_t)constrain((abs(amperage) * 10), 0, 0xFFFF)); // send amperage in 0.001 A steps
} else
serialize16((uint16_t)constrain(abs(amperage), 0, 0xFFFF)); // send amperage in 0.01 A steps
serialize16((uint16_t)constrain(abs(amperage), 0, 0xFFFF)); // send amperage in 0.01 A steps
break;
case MSP_RC_TUNING:
headSerialReply(7);

View file

@ -1,60 +1,60 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "drivers/system.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "rx/msp.h"
static bool rxMspFrameDone = false;
static uint16_t rxMspReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
return rcData[chan];
}
void rxMspFrameRecieve(void)
{
rxMspFrameDone = true;
}
bool rxMspFrameComplete(void)
{
if (rxMspFrameDone) {
rxMspFrameDone = false;
return true;
}
return false;
}
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{
rxRuntimeConfig->channelCount = 8; // See MSP_SET_RAW_RC
if (callback)
*callback = rxMspReadRawRC;
return true;
}
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "drivers/system.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "rx/msp.h"
static bool rxMspFrameDone = false;
static uint16_t rxMspReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
return rcData[chan];
}
void rxMspFrameRecieve(void)
{
rxMspFrameDone = true;
}
bool rxMspFrameComplete(void)
{
if (rxMspFrameDone) {
rxMspFrameDone = false;
return true;
}
return false;
}
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{
rxRuntimeConfig->channelCount = 8; // See MSP_SET_RAW_RC
if (callback)
*callback = rxMspReadRawRC;
return true;
}

View file

@ -51,17 +51,17 @@
*-----------------------------------------------------------------------------
* AHB Prescaler | 1
*-----------------------------------------------------------------------------
* APB2 Prescaler | 2
* APB2 Prescaler | 2
*-----------------------------------------------------------------------------
* APB1 Prescaler | 2
*-----------------------------------------------------------------------------
* HSE Frequency(Hz) | 12000000
* HSE Frequency(Hz) | 12000000
*----------------------------------------------------------------------------
* PLLMUL | 6
* PLLMUL | 6
*-----------------------------------------------------------------------------
* PREDIV | 1
*-----------------------------------------------------------------------------
* USB Clock | ENABLE
* USB Clock | ENABLE
*-----------------------------------------------------------------------------
* Flash Latency(WS) | 2
*-----------------------------------------------------------------------------

View file

@ -51,17 +51,17 @@
*-----------------------------------------------------------------------------
* AHB Prescaler | 1
*-----------------------------------------------------------------------------
* APB2 Prescaler | 2
* APB2 Prescaler | 2
*-----------------------------------------------------------------------------
* APB1 Prescaler | 2
*-----------------------------------------------------------------------------
* HSE Frequency(Hz) | 12000000
* HSE Frequency(Hz) | 12000000
*----------------------------------------------------------------------------
* PLLMUL | 6
* PLLMUL | 6
*-----------------------------------------------------------------------------
* PREDIV | 1
*-----------------------------------------------------------------------------
* USB Clock | ENABLE
* USB Clock | ENABLE
*-----------------------------------------------------------------------------
* Flash Latency(WS) | 2
*-----------------------------------------------------------------------------

View file

@ -51,17 +51,17 @@
*-----------------------------------------------------------------------------
* AHB Prescaler | 1
*-----------------------------------------------------------------------------
* APB2 Prescaler | 2
* APB2 Prescaler | 2
*-----------------------------------------------------------------------------
* APB1 Prescaler | 2
*-----------------------------------------------------------------------------
* HSE Frequency(Hz) | 12000000
* HSE Frequency(Hz) | 12000000
*----------------------------------------------------------------------------
* PLLMUL | 6
* PLLMUL | 6
*-----------------------------------------------------------------------------
* PREDIV | 1
*-----------------------------------------------------------------------------
* USB Clock | ENABLE
* USB Clock | ENABLE
*-----------------------------------------------------------------------------
* Flash Latency(WS) | 2
*-----------------------------------------------------------------------------

View file

@ -1,353 +1,353 @@
/**
******************************************************************************
* @file hw_config.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Hardware Configuration & Setup
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32_it.h"
#include "platform.h"
#include "usb_lib.h"
#include "usb_prop.h"
#include "usb_desc.h"
#include "hw_config.h"
#include "usb_pwr.h"
#include <stdbool.h>
#include "drivers/system.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
ErrorStatus HSEStartUpStatus;
EXTI_InitTypeDef EXTI_InitStructure;
__IO uint32_t packetSent; // HJI
extern __IO uint32_t receiveLength; // HJI
uint8_t receiveBuffer[64]; // HJI
uint32_t sendLength; // HJI
static void IntToUnicode(uint32_t value, uint8_t *pbuf, uint8_t len);
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : Set_System
* Description : Configures Main system clocks & power
* Input : None.
* Return : None.
*******************************************************************************/
void Set_System(void)
{
#if !defined(STM32L1XX_MD) && !defined(STM32L1XX_HD) && !defined(STM32L1XX_MD_PLUS)
GPIO_InitTypeDef GPIO_InitStructure;
#endif /* STM32L1XX_MD && STM32L1XX_XD */
#if defined(USB_USE_EXTERNAL_PULLUP)
GPIO_InitTypeDef GPIO_InitStructure;
#endif /* USB_USE_EXTERNAL_PULLUP */
/*!< At this stage the microcontroller clock setting is already configured,
this is done through SystemInit() function which is called from startup
file (startup_stm32f10x_xx.s) before to branch to application main.
To reconfigure the default setting of SystemInit() function, refer to
system_stm32f10x.c file
*/
#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS) || defined(STM32F37X) || defined(STM32F303xC)
/* Enable the SYSCFG module clock */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
#endif /* STM32L1XX_XD */
/*Pull down PA12 to create USB Disconnect Pulse*/ // HJI
#if defined(STM32F303xC) // HJI
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE); // HJI
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; // HJI
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; // HJI
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; // HJI
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD; // HJI
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; // HJI
#else
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); // HJI
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;// HJI
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;// HJI
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;// HJI
#endif
GPIO_Init(GPIOA, &GPIO_InitStructure); // HJI
GPIO_ResetBits(GPIOA, GPIO_Pin_12); // HJI
delay(200); // HJI
GPIO_SetBits(GPIOA, GPIO_Pin_12); // HJI
#if defined(STM32F37X) || defined(STM32F303xC)
/*Set PA11,12 as IN - USB_DM,DP*/
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(GPIOA, &GPIO_InitStructure);
/*SET PA11,12 for USB: USB_DM,DP*/
GPIO_PinAFConfig(GPIOA, GPIO_PinSource11, GPIO_AF_14);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource12, GPIO_AF_14);
#endif /* STM32F37X && STM32F303xC)*/
/* Configure the EXTI line 18 connected internally to the USB IP */
EXTI_ClearITPendingBit(EXTI_Line18);
EXTI_InitStructure.EXTI_Line = EXTI_Line18;
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTI_InitStructure);
}
/*******************************************************************************
* Function Name : Set_USBClock
* Description : Configures USB Clock input (48MHz)
* Input : None.
* Return : None.
*******************************************************************************/
void Set_USBClock(void)
{
/* Select USBCLK source */
RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5);
/* Enable the USB clock */
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE);
}
/*******************************************************************************
* Function Name : Enter_LowPowerMode
* Description : Power-off system clocks and power while entering suspend mode
* Input : None.
* Return : None.
*******************************************************************************/
void Enter_LowPowerMode(void)
{
/* Set the device state to suspend */
bDeviceState = SUSPENDED;
}
/*******************************************************************************
* Function Name : Leave_LowPowerMode
* Description : Restores system clocks and power while exiting suspend mode
* Input : None.
* Return : None.
*******************************************************************************/
void Leave_LowPowerMode(void)
{
DEVICE_INFO *pInfo = &Device_Info;
/* Set the device state to the correct state */
if (pInfo->Current_Configuration != 0) {
/* Device configured */
bDeviceState = CONFIGURED;
} else {
bDeviceState = ATTACHED;
}
/*Enable SystemCoreClock*/
SystemInit();
}
/*******************************************************************************
* Function Name : USB_Interrupts_Config
* Description : Configures the USB interrupts
* Input : None.
* Return : None.
*******************************************************************************/
void USB_Interrupts_Config(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
/* 2 bit for pre-emption priority, 2 bits for subpriority */
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
/* Enable the USB interrupt */
NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
/* Enable the USB Wake-up interrupt */
NVIC_InitStructure.NVIC_IRQChannel = USBWakeUp_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_Init(&NVIC_InitStructure);
}
/*******************************************************************************
* Function Name : USB_Cable_Config
* Description : Software Connection/Disconnection of USB Cable
* Input : None.
* Return : Status
*******************************************************************************/
void USB_Cable_Config(FunctionalState NewState)
{
}
/*******************************************************************************
* Function Name : Get_SerialNum.
* Description : Create the serial number string descriptor.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Get_SerialNum(void)
{
uint32_t Device_Serial0, Device_Serial1, Device_Serial2;
Device_Serial0 = *(uint32_t*)ID1;
Device_Serial1 = *(uint32_t*)ID2;
Device_Serial2 = *(uint32_t*)ID3;
Device_Serial0 += Device_Serial2;
if (Device_Serial0 != 0) {
IntToUnicode(Device_Serial0, &Virtual_Com_Port_StringSerial[2], 8);
IntToUnicode(Device_Serial1, &Virtual_Com_Port_StringSerial[18], 4);
}
}
/*******************************************************************************
* Function Name : HexToChar.
* Description : Convert Hex 32Bits value into char.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
static void IntToUnicode(uint32_t value, uint8_t *pbuf, uint8_t len)
{
uint8_t idx = 0;
for (idx = 0; idx < len; idx++) {
if (((value >> 28)) < 0xA) {
pbuf[2 * idx] = (value >> 28) + '0';
} else {
pbuf[2 * idx] = (value >> 28) + 'A' - 10;
}
value = value << 4;
pbuf[2 * idx + 1] = 0;
}
}
/*******************************************************************************
* Function Name : Send DATA .
* Description : send the data received from the STM32 to the PC through USB
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength)
{
/* Last transmission hasn't finished, abort */
if (packetSent) {
return 0;
}
// We can only put 64 bytes in the buffer
if (sendLength > 64 / 2) {
sendLength = 64 / 2;
}
// Try to load some bytes if we can
if (sendLength) {
UserToPMABufferCopy(ptrBuffer, ENDP1_TXADDR, sendLength);
SetEPTxCount(ENDP1, sendLength);
packetSent += sendLength;
SetEPTxValid(ENDP1);
}
return sendLength;
}
/*******************************************************************************
* Function Name : Receive DATA .
* Description : receive the data from the PC to STM32 and send it through USB
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
{
static uint8_t offset = 0;
uint8_t i;
if (len > receiveLength) {
len = receiveLength;
}
for (i = 0; i < len; i++) {
recvBuf[i] = (uint8_t)(receiveBuffer[i + offset]);
}
receiveLength -= len;
offset += len;
/* re-enable the rx endpoint which we had set to receive 0 bytes */
if (receiveLength == 0) {
SetEPRxCount(ENDP3, 64);
SetEPRxStatus(ENDP3, EP_RX_VALID);
offset = 0;
}
return len;
}
/*******************************************************************************
* Function Name : usbIsConfigured.
* Description : Determines if USB VCP is configured or not
* Input : None.
* Output : None.
* Return : True if configured.
*******************************************************************************/
uint8_t usbIsConfigured(void)
{
return (bDeviceState == CONFIGURED);
}
/*******************************************************************************
* Function Name : usbIsConnected.
* Description : Determines if USB VCP is connected ot not
* Input : None.
* Output : None.
* Return : True if connected.
*******************************************************************************/
uint8_t usbIsConnected(void)
{
return (bDeviceState != UNCONNECTED);
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file hw_config.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Hardware Configuration & Setup
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32_it.h"
#include "platform.h"
#include "usb_lib.h"
#include "usb_prop.h"
#include "usb_desc.h"
#include "hw_config.h"
#include "usb_pwr.h"
#include <stdbool.h>
#include "drivers/system.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
ErrorStatus HSEStartUpStatus;
EXTI_InitTypeDef EXTI_InitStructure;
__IO uint32_t packetSent; // HJI
extern __IO uint32_t receiveLength; // HJI
uint8_t receiveBuffer[64]; // HJI
uint32_t sendLength; // HJI
static void IntToUnicode(uint32_t value, uint8_t *pbuf, uint8_t len);
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : Set_System
* Description : Configures Main system clocks & power
* Input : None.
* Return : None.
*******************************************************************************/
void Set_System(void)
{
#if !defined(STM32L1XX_MD) && !defined(STM32L1XX_HD) && !defined(STM32L1XX_MD_PLUS)
GPIO_InitTypeDef GPIO_InitStructure;
#endif /* STM32L1XX_MD && STM32L1XX_XD */
#if defined(USB_USE_EXTERNAL_PULLUP)
GPIO_InitTypeDef GPIO_InitStructure;
#endif /* USB_USE_EXTERNAL_PULLUP */
/*!< At this stage the microcontroller clock setting is already configured,
this is done through SystemInit() function which is called from startup
file (startup_stm32f10x_xx.s) before to branch to application main.
To reconfigure the default setting of SystemInit() function, refer to
system_stm32f10x.c file
*/
#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS) || defined(STM32F37X) || defined(STM32F303xC)
/* Enable the SYSCFG module clock */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
#endif /* STM32L1XX_XD */
/*Pull down PA12 to create USB Disconnect Pulse*/ // HJI
#if defined(STM32F303xC) // HJI
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE); // HJI
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; // HJI
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; // HJI
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; // HJI
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD; // HJI
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; // HJI
#else
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); // HJI
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;// HJI
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;// HJI
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;// HJI
#endif
GPIO_Init(GPIOA, &GPIO_InitStructure); // HJI
GPIO_ResetBits(GPIOA, GPIO_Pin_12); // HJI
delay(200); // HJI
GPIO_SetBits(GPIOA, GPIO_Pin_12); // HJI
#if defined(STM32F37X) || defined(STM32F303xC)
/*Set PA11,12 as IN - USB_DM,DP*/
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(GPIOA, &GPIO_InitStructure);
/*SET PA11,12 for USB: USB_DM,DP*/
GPIO_PinAFConfig(GPIOA, GPIO_PinSource11, GPIO_AF_14);
GPIO_PinAFConfig(GPIOA, GPIO_PinSource12, GPIO_AF_14);
#endif /* STM32F37X && STM32F303xC)*/
/* Configure the EXTI line 18 connected internally to the USB IP */
EXTI_ClearITPendingBit(EXTI_Line18);
EXTI_InitStructure.EXTI_Line = EXTI_Line18;
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTI_InitStructure);
}
/*******************************************************************************
* Function Name : Set_USBClock
* Description : Configures USB Clock input (48MHz)
* Input : None.
* Return : None.
*******************************************************************************/
void Set_USBClock(void)
{
/* Select USBCLK source */
RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5);
/* Enable the USB clock */
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE);
}
/*******************************************************************************
* Function Name : Enter_LowPowerMode
* Description : Power-off system clocks and power while entering suspend mode
* Input : None.
* Return : None.
*******************************************************************************/
void Enter_LowPowerMode(void)
{
/* Set the device state to suspend */
bDeviceState = SUSPENDED;
}
/*******************************************************************************
* Function Name : Leave_LowPowerMode
* Description : Restores system clocks and power while exiting suspend mode
* Input : None.
* Return : None.
*******************************************************************************/
void Leave_LowPowerMode(void)
{
DEVICE_INFO *pInfo = &Device_Info;
/* Set the device state to the correct state */
if (pInfo->Current_Configuration != 0) {
/* Device configured */
bDeviceState = CONFIGURED;
} else {
bDeviceState = ATTACHED;
}
/*Enable SystemCoreClock*/
SystemInit();
}
/*******************************************************************************
* Function Name : USB_Interrupts_Config
* Description : Configures the USB interrupts
* Input : None.
* Return : None.
*******************************************************************************/
void USB_Interrupts_Config(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
/* 2 bit for pre-emption priority, 2 bits for subpriority */
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
/* Enable the USB interrupt */
NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
/* Enable the USB Wake-up interrupt */
NVIC_InitStructure.NVIC_IRQChannel = USBWakeUp_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_Init(&NVIC_InitStructure);
}
/*******************************************************************************
* Function Name : USB_Cable_Config
* Description : Software Connection/Disconnection of USB Cable
* Input : None.
* Return : Status
*******************************************************************************/
void USB_Cable_Config(FunctionalState NewState)
{
}
/*******************************************************************************
* Function Name : Get_SerialNum.
* Description : Create the serial number string descriptor.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Get_SerialNum(void)
{
uint32_t Device_Serial0, Device_Serial1, Device_Serial2;
Device_Serial0 = *(uint32_t*)ID1;
Device_Serial1 = *(uint32_t*)ID2;
Device_Serial2 = *(uint32_t*)ID3;
Device_Serial0 += Device_Serial2;
if (Device_Serial0 != 0) {
IntToUnicode(Device_Serial0, &Virtual_Com_Port_StringSerial[2], 8);
IntToUnicode(Device_Serial1, &Virtual_Com_Port_StringSerial[18], 4);
}
}
/*******************************************************************************
* Function Name : HexToChar.
* Description : Convert Hex 32Bits value into char.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
static void IntToUnicode(uint32_t value, uint8_t *pbuf, uint8_t len)
{
uint8_t idx = 0;
for (idx = 0; idx < len; idx++) {
if (((value >> 28)) < 0xA) {
pbuf[2 * idx] = (value >> 28) + '0';
} else {
pbuf[2 * idx] = (value >> 28) + 'A' - 10;
}
value = value << 4;
pbuf[2 * idx + 1] = 0;
}
}
/*******************************************************************************
* Function Name : Send DATA .
* Description : send the data received from the STM32 to the PC through USB
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength)
{
/* Last transmission hasn't finished, abort */
if (packetSent) {
return 0;
}
// We can only put 64 bytes in the buffer
if (sendLength > 64 / 2) {
sendLength = 64 / 2;
}
// Try to load some bytes if we can
if (sendLength) {
UserToPMABufferCopy(ptrBuffer, ENDP1_TXADDR, sendLength);
SetEPTxCount(ENDP1, sendLength);
packetSent += sendLength;
SetEPTxValid(ENDP1);
}
return sendLength;
}
/*******************************************************************************
* Function Name : Receive DATA .
* Description : receive the data from the PC to STM32 and send it through USB
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len)
{
static uint8_t offset = 0;
uint8_t i;
if (len > receiveLength) {
len = receiveLength;
}
for (i = 0; i < len; i++) {
recvBuf[i] = (uint8_t)(receiveBuffer[i + offset]);
}
receiveLength -= len;
offset += len;
/* re-enable the rx endpoint which we had set to receive 0 bytes */
if (receiveLength == 0) {
SetEPRxCount(ENDP3, 64);
SetEPRxStatus(ENDP3, EP_RX_VALID);
offset = 0;
}
return len;
}
/*******************************************************************************
* Function Name : usbIsConfigured.
* Description : Determines if USB VCP is configured or not
* Input : None.
* Output : None.
* Return : True if configured.
*******************************************************************************/
uint8_t usbIsConfigured(void)
{
return (bDeviceState == CONFIGURED);
}
/*******************************************************************************
* Function Name : usbIsConnected.
* Description : Determines if USB VCP is connected ot not
* Input : None.
* Output : None.
* Return : True if connected.
*******************************************************************************/
uint8_t usbIsConnected(void)
{
return (bDeviceState != UNCONNECTED);
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,62 +1,62 @@
/**
******************************************************************************
* @file hw_config.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Hardware Configuration & Setup
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __HW_CONFIG_H
#define __HW_CONFIG_H
/* Includes ------------------------------------------------------------------*/
//#include "platform_config.h"
#include "usb_type.h"
#include "stm32f30x.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported define -----------------------------------------------------------*/
#define MASS_MEMORY_START 0x04002000
#define BULK_MAX_PACKET_SIZE 0x00000040
/* Exported functions ------------------------------------------------------- */
void Set_System(void);
void Set_USBClock(void);
void Enter_LowPowerMode(void);
void Leave_LowPowerMode(void);
void USB_Interrupts_Config(void);
void USB_Cable_Config(FunctionalState NewState);
void Get_SerialNum(void);
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength); // HJI
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len); // HJI
uint8_t usbIsConfigured(void); // HJI
uint8_t usbIsConnected(void); // HJI
/* External variables --------------------------------------------------------*/
extern __IO uint32_t receiveLength; // HJI
extern __IO uint32_t packetSent; // HJI
#endif /*__HW_CONFIG_H*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file hw_config.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Hardware Configuration & Setup
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __HW_CONFIG_H
#define __HW_CONFIG_H
/* Includes ------------------------------------------------------------------*/
//#include "platform_config.h"
#include "usb_type.h"
#include "stm32f30x.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported define -----------------------------------------------------------*/
#define MASS_MEMORY_START 0x04002000
#define BULK_MAX_PACKET_SIZE 0x00000040
/* Exported functions ------------------------------------------------------- */
void Set_System(void);
void Set_USBClock(void);
void Enter_LowPowerMode(void);
void Leave_LowPowerMode(void);
void USB_Interrupts_Config(void);
void USB_Cable_Config(FunctionalState NewState);
void Get_SerialNum(void);
uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength); // HJI
uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len); // HJI
uint8_t usbIsConfigured(void); // HJI
uint8_t usbIsConnected(void); // HJI
/* External variables --------------------------------------------------------*/
extern __IO uint32_t receiveLength; // HJI
extern __IO uint32_t packetSent; // HJI
#endif /*__HW_CONFIG_H*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,63 +1,63 @@
/**
******************************************************************************
* @file platform_config.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Evaluation board specific configuration file.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __PLATFORM_CONFIG_H
#define __PLATFORM_CONFIG_H
/* Includes ------------------------------------------------------------------*/
#if defined (STM32F10X_MD) || defined (STM32F10X_HD)
#include "stm32f10x.h"
#elif defined (STM32F303xC)
#include "stm32f30x.h"
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/*Unique Devices IDs register set*/
#if defined (STM32F37X) || defined(STM32F303xC)
#define ID1 (0x1FFFF7AC)
#define ID2 (0x1FFFF7B0)
#define ID3 (0x1FFFF7B4)
#else /*STM32F1x*/
#define ID1 (0x1FFFF7E8)
#define ID2 (0x1FFFF7EC)
#define ID3 (0x1FFFF7F0)
#endif
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
#endif /* __PLATFORM_CONFIG_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file platform_config.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Evaluation board specific configuration file.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __PLATFORM_CONFIG_H
#define __PLATFORM_CONFIG_H
/* Includes ------------------------------------------------------------------*/
#if defined (STM32F10X_MD) || defined (STM32F10X_HD)
#include "stm32f10x.h"
#elif defined (STM32F303xC)
#include "stm32f30x.h"
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/*Unique Devices IDs register set*/
#if defined (STM32F37X) || defined(STM32F303xC)
#define ID1 (0x1FFFF7AC)
#define ID2 (0x1FFFF7B0)
#define ID3 (0x1FFFF7B4)
#else /*STM32F1x*/
#define ID1 (0x1FFFF7E8)
#define ID2 (0x1FFFF7EC)
#define ID3 (0x1FFFF7F0)
#endif
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
#endif /* __PLATFORM_CONFIG_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,167 +1,167 @@
/**
******************************************************************************
* @file stm32_it.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Main Interrupt Service Routines.
* This file provides template for all exceptions handler and peripherals
* interrupt service routine.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "hw_config.h"
#include "stm32_it.h"
#include "usb_lib.h"
#include "vcp/usb_istr.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/******************************************************************************/
/* Cortex-M Processor Exceptions Handlers */
/******************************************************************************/
/*******************************************************************************
* Function Name : NMI_Handler
* Description : This function handles NMI exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void NMI_Handler(void)
{
}
/*******************************************************************************
* Function Name : MemManage_Handler
* Description : This function handles Memory Manage exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void MemManage_Handler(void)
{
/* Go to infinite loop when Memory Manage exception occurs */
while (1) {
}
}
/*******************************************************************************
* Function Name : BusFault_Handler
* Description : This function handles Bus Fault exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void BusFault_Handler(void)
{
/* Go to infinite loop when Bus Fault exception occurs */
while (1) {
}
}
/*******************************************************************************
* Function Name : UsageFault_Handler
* Description : This function handles Usage Fault exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void UsageFault_Handler(void)
{
/* Go to infinite loop when Usage Fault exception occurs */
while (1) {
}
}
/*******************************************************************************
* Function Name : SVC_Handler
* Description : This function handles SVCall exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void SVC_Handler(void)
{
}
/*******************************************************************************
* Function Name : DebugMon_Handler
* Description : This function handles Debug Monitor exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void DebugMon_Handler(void)
{
}
/*******************************************************************************
* Function Name : PendSV_Handler
* Description : This function handles PendSVC exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void PendSV_Handler(void)
{
}
/*******************************************************************************
* Function Name : USB_IRQHandler
* Description : This function handles USB Low Priority interrupts
* requests.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS)|| defined (STM32F37X)
void USB_LP_IRQHandler(void)
#else
void USB_LP_CAN1_RX0_IRQHandler(void)
#endif
{
USB_Istr();
}
/*******************************************************************************
* Function Name : USB_FS_WKUP_IRQHandler
* Description : This function handles USB WakeUp interrupt request.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS)
void USB_FS_WKUP_IRQHandler(void)
#else
void USBWakeUp_IRQHandler(void)
#endif
{
EXTI_ClearITPendingBit(EXTI_Line18);
}
/**
******************************************************************************
* @file stm32_it.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Main Interrupt Service Routines.
* This file provides template for all exceptions handler and peripherals
* interrupt service routine.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "hw_config.h"
#include "stm32_it.h"
#include "usb_lib.h"
#include "vcp/usb_istr.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/******************************************************************************/
/* Cortex-M Processor Exceptions Handlers */
/******************************************************************************/
/*******************************************************************************
* Function Name : NMI_Handler
* Description : This function handles NMI exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void NMI_Handler(void)
{
}
/*******************************************************************************
* Function Name : MemManage_Handler
* Description : This function handles Memory Manage exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void MemManage_Handler(void)
{
/* Go to infinite loop when Memory Manage exception occurs */
while (1) {
}
}
/*******************************************************************************
* Function Name : BusFault_Handler
* Description : This function handles Bus Fault exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void BusFault_Handler(void)
{
/* Go to infinite loop when Bus Fault exception occurs */
while (1) {
}
}
/*******************************************************************************
* Function Name : UsageFault_Handler
* Description : This function handles Usage Fault exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void UsageFault_Handler(void)
{
/* Go to infinite loop when Usage Fault exception occurs */
while (1) {
}
}
/*******************************************************************************
* Function Name : SVC_Handler
* Description : This function handles SVCall exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void SVC_Handler(void)
{
}
/*******************************************************************************
* Function Name : DebugMon_Handler
* Description : This function handles Debug Monitor exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void DebugMon_Handler(void)
{
}
/*******************************************************************************
* Function Name : PendSV_Handler
* Description : This function handles PendSVC exception.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void PendSV_Handler(void)
{
}
/*******************************************************************************
* Function Name : USB_IRQHandler
* Description : This function handles USB Low Priority interrupts
* requests.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS)|| defined (STM32F37X)
void USB_LP_IRQHandler(void)
#else
void USB_LP_CAN1_RX0_IRQHandler(void)
#endif
{
USB_Istr();
}
/*******************************************************************************
* Function Name : USB_FS_WKUP_IRQHandler
* Description : This function handles USB WakeUp interrupt request.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
#if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS)
void USB_FS_WKUP_IRQHandler(void)
#else
void USBWakeUp_IRQHandler(void)
#endif
{
EXTI_ClearITPendingBit(EXTI_Line18);
}

View file

@ -1,53 +1,53 @@
/**
******************************************************************************
* @file stm32_it.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief This file contains the headers of the interrupt handlers.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32_IT_H
#define __STM32_IT_H
/* Includes ------------------------------------------------------------------*/
#include "platform_config.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void NMI_Handler(void);
void MemManage_Handler(void);
void BusFault_Handler(void);
void UsageFault_Handler(void);
void SVC_Handler(void);
void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void USBWakeUp_IRQHandler(void);
void USB_FS_WKUP_IRQHandler(void);
#endif /* __STM32_IT_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file stm32_it.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief This file contains the headers of the interrupt handlers.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32_IT_H
#define __STM32_IT_H
/* Includes ------------------------------------------------------------------*/
#include "platform_config.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void NMI_Handler(void);
void MemManage_Handler(void);
void BusFault_Handler(void);
void UsageFault_Handler(void);
void SVC_Handler(void);
void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void USBWakeUp_IRQHandler(void);
void USB_FS_WKUP_IRQHandler(void);
#endif /* __STM32_IT_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,102 +1,102 @@
/**
******************************************************************************
* @file usb_conf.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Virtual COM Port Demo configuration header
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_CONF_H
#define __USB_CONF_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
/* External variables --------------------------------------------------------*/
/*-------------------------------------------------------------*/
/* EP_NUM */
/* defines how many endpoints are used by the device */
/*-------------------------------------------------------------*/
#define EP_NUM (4)
/*-------------------------------------------------------------*/
/* -------------- Buffer Description Table -----------------*/
/*-------------------------------------------------------------*/
/* buffer table base address */
/* buffer table base address */
#define BTABLE_ADDRESS (0x00)
/* EP0 */
/* rx/tx buffer base address */
#define ENDP0_RXADDR (0x40)
#define ENDP0_TXADDR (0x80)
/* EP1 */
/* tx buffer base address */
#define ENDP1_TXADDR (0xC0)
#define ENDP2_TXADDR (0x100)
#define ENDP3_RXADDR (0x110)
/*-------------------------------------------------------------*/
/* ------------------- ISTR events -------------------------*/
/*-------------------------------------------------------------*/
/* IMR_MSK */
/* mask defining which events has to be handled */
/* by the device application software */
// HJI #define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_SUSPM | CNTR_ERRM | CNTR_SOFM | CNTR_ESOFM | CNTR_RESETM )
// Disable Suspend/Resume response completely // HJI
#define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_ERRM | CNTR_SOFM | CNTR_RESETM ) // HJI
/*#define CTR_CALLBACK*/
/*#define DOVR_CALLBACK*/
/*#define ERR_CALLBACK*/
/*#define WKUP_CALLBACK*/
/*#define SUSP_CALLBACK*/
/*#define RESET_CALLBACK*/
/*#define SOF_CALLBACK*/
/*#define ESOF_CALLBACK*/
/* CTR service routines */
/* associated to defined endpoints */
/*#define EP1_IN_Callback NOP_Process*/
#define EP2_IN_Callback NOP_Process
#define EP3_IN_Callback NOP_Process
#define EP4_IN_Callback NOP_Process
#define EP5_IN_Callback NOP_Process
#define EP6_IN_Callback NOP_Process
#define EP7_IN_Callback NOP_Process
#define EP1_OUT_Callback NOP_Process
#define EP2_OUT_Callback NOP_Process
/*#define EP3_OUT_Callback NOP_Process*/
#define EP4_OUT_Callback NOP_Process
#define EP5_OUT_Callback NOP_Process
#define EP6_OUT_Callback NOP_Process
#define EP7_OUT_Callback NOP_Process
#endif /* __USB_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file usb_conf.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Virtual COM Port Demo configuration header
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_CONF_H
#define __USB_CONF_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
/* External variables --------------------------------------------------------*/
/*-------------------------------------------------------------*/
/* EP_NUM */
/* defines how many endpoints are used by the device */
/*-------------------------------------------------------------*/
#define EP_NUM (4)
/*-------------------------------------------------------------*/
/* -------------- Buffer Description Table -----------------*/
/*-------------------------------------------------------------*/
/* buffer table base address */
/* buffer table base address */
#define BTABLE_ADDRESS (0x00)
/* EP0 */
/* rx/tx buffer base address */
#define ENDP0_RXADDR (0x40)
#define ENDP0_TXADDR (0x80)
/* EP1 */
/* tx buffer base address */
#define ENDP1_TXADDR (0xC0)
#define ENDP2_TXADDR (0x100)
#define ENDP3_RXADDR (0x110)
/*-------------------------------------------------------------*/
/* ------------------- ISTR events -------------------------*/
/*-------------------------------------------------------------*/
/* IMR_MSK */
/* mask defining which events has to be handled */
/* by the device application software */
// HJI #define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_SUSPM | CNTR_ERRM | CNTR_SOFM | CNTR_ESOFM | CNTR_RESETM )
// Disable Suspend/Resume response completely // HJI
#define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_ERRM | CNTR_SOFM | CNTR_RESETM ) // HJI
/*#define CTR_CALLBACK*/
/*#define DOVR_CALLBACK*/
/*#define ERR_CALLBACK*/
/*#define WKUP_CALLBACK*/
/*#define SUSP_CALLBACK*/
/*#define RESET_CALLBACK*/
/*#define SOF_CALLBACK*/
/*#define ESOF_CALLBACK*/
/* CTR service routines */
/* associated to defined endpoints */
/*#define EP1_IN_Callback NOP_Process*/
#define EP2_IN_Callback NOP_Process
#define EP3_IN_Callback NOP_Process
#define EP4_IN_Callback NOP_Process
#define EP5_IN_Callback NOP_Process
#define EP6_IN_Callback NOP_Process
#define EP7_IN_Callback NOP_Process
#define EP1_OUT_Callback NOP_Process
#define EP2_OUT_Callback NOP_Process
/*#define EP3_OUT_Callback NOP_Process*/
#define EP4_OUT_Callback NOP_Process
#define EP5_OUT_Callback NOP_Process
#define EP6_OUT_Callback NOP_Process
#define EP7_OUT_Callback NOP_Process
#endif /* __USB_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,149 +1,149 @@
/**
******************************************************************************
* @file usb_desc.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Descriptors for Virtual Com Port Demo
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_lib.h"
#include "usb_desc.h"
/* USB Standard Device Descriptor */
const uint8_t Virtual_Com_Port_DeviceDescriptor[] = { 0x12, /* bLength */
USB_DEVICE_DESCRIPTOR_TYPE, /* bDescriptorType */
0x00, 0x02, /* bcdUSB = 2.00 */
0x02, /* bDeviceClass: CDC */
0x00, /* bDeviceSubClass */
0x00, /* bDeviceProtocol */
0x40, /* bMaxPacketSize0 */
0x83, 0x04, /* idVendor = 0x0483 */
0x40, 0x57, /* idProduct = 0x7540 */
0x00, 0x02, /* bcdDevice = 2.00 */
1, /* Index of string descriptor describing manufacturer */
2, /* Index of string descriptor describing product */
3, /* Index of string descriptor describing the device's serial number */
0x01 /* bNumConfigurations */
};
const uint8_t Virtual_Com_Port_ConfigDescriptor[] = {
/*Configuration Descriptor*/
0x09, /* bLength: Configuration Descriptor size */
USB_CONFIGURATION_DESCRIPTOR_TYPE, /* bDescriptorType: Configuration */
VIRTUAL_COM_PORT_SIZ_CONFIG_DESC, /* wTotalLength:no of returned bytes */
0x00, 0x02, /* bNumInterfaces: 2 interface */
0x01, /* bConfigurationValue: Configuration value */
0x00, /* iConfiguration: Index of string descriptor describing the configuration */
0xC0, /* bmAttributes: self powered */
0x32, /* MaxPower 0 mA */
/*Interface Descriptor*/
0x09, /* bLength: Interface Descriptor size */
USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType: Interface */
/* Interface descriptor type */
0x00, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x01, /* bNumEndpoints: One endpoints used */
0x02, /* bInterfaceClass: Communication Interface Class */
0x02, /* bInterfaceSubClass: Abstract Control Model */
0x01, /* bInterfaceProtocol: Common AT commands */
0x00, /* iInterface: */
/*Header Functional Descriptor*/
0x05, /* bLength: Endpoint Descriptor size */
0x24, /* bDescriptorType: CS_INTERFACE */
0x00, /* bDescriptorSubtype: Header Func Desc */
0x10, /* bcdCDC: spec release number */
0x01,
/*Call Management Functional Descriptor*/
0x05, /* bFunctionLength */
0x24, /* bDescriptorType: CS_INTERFACE */
0x01, /* bDescriptorSubtype: Call Management Func Desc */
0x00, /* bmCapabilities: D0+D1 */
0x01, /* bDataInterface: 1 */
/*ACM Functional Descriptor*/
0x04, /* bFunctionLength */
0x24, /* bDescriptorType: CS_INTERFACE */
0x02, /* bDescriptorSubtype: Abstract Control Management desc */
0x02, /* bmCapabilities */
/*Union Functional Descriptor*/
0x05, /* bFunctionLength */
0x24, /* bDescriptorType: CS_INTERFACE */
0x06, /* bDescriptorSubtype: Union func desc */
0x00, /* bMasterInterface: Communication class interface */
0x01, /* bSlaveInterface0: Data Class Interface */
/*Endpoint 2 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
0x82, /* bEndpointAddress: (IN2) */
0x03, /* bmAttributes: Interrupt */
VIRTUAL_COM_PORT_INT_SIZE, /* wMaxPacketSize: */
0x00, 0xFF, /* bInterval: */
/*Data class interface descriptor*/
0x09, /* bLength: Endpoint Descriptor size */
USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType: */
0x01, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x02, /* bNumEndpoints: Two endpoints used */
0x0A, /* bInterfaceClass: CDC */
0x00, /* bInterfaceSubClass: */
0x00, /* bInterfaceProtocol: */
0x00, /* iInterface: */
/*Endpoint 3 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
0x03, /* bEndpointAddress: (OUT3) */
0x02, /* bmAttributes: Bulk */
VIRTUAL_COM_PORT_DATA_SIZE, /* wMaxPacketSize: */
0x00, 0x00, /* bInterval: ignore for Bulk transfer */
/*Endpoint 1 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
0x81, /* bEndpointAddress: (IN1) */
0x02, /* bmAttributes: Bulk */
VIRTUAL_COM_PORT_DATA_SIZE, /* wMaxPacketSize: */
0x00, 0x00 /* bInterval */
};
/* USB String Descriptors */
const uint8_t Virtual_Com_Port_StringLangID[VIRTUAL_COM_PORT_SIZ_STRING_LANGID] = {
VIRTUAL_COM_PORT_SIZ_STRING_LANGID,
USB_STRING_DESCRIPTOR_TYPE, 0x09, 0x04 /* LangID = 0x0409: U.S. English */
};
const uint8_t Virtual_Com_Port_StringVendor[VIRTUAL_COM_PORT_SIZ_STRING_VENDOR] = {
VIRTUAL_COM_PORT_SIZ_STRING_VENDOR, /* Size of Vendor string */
USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType*/
/* Manufacturer: "STMicroelectronics" */
'S', 0, 'T', 0, 'M', 0, 'i', 0, 'c', 0, 'r', 0, 'o', 0, 'e', 0, 'l', 0, 'e', 0, 'c', 0, 't', 0, 'r', 0, 'o', 0, 'n', 0, 'i', 0, 'c', 0, 's', 0 };
const uint8_t Virtual_Com_Port_StringProduct[VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT] = {
VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT, /* bLength */
USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
/* Product name: "STM32 Virtual COM Port" */
'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0, ' ', 0, 'V', 0, 'i', 0, 'r', 0, 't', 0, 'u', 0, 'a', 0, 'l', 0, ' ', 0, 'C', 0, 'O', 0, 'M', 0, ' ', 0, 'P', 0, 'o', 0, 'r', 0, 't', 0, ' ', 0, ' ', 0 };
uint8_t Virtual_Com_Port_StringSerial[VIRTUAL_COM_PORT_SIZ_STRING_SERIAL] = {
VIRTUAL_COM_PORT_SIZ_STRING_SERIAL, /* bLength */
USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0 };
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file usb_desc.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Descriptors for Virtual Com Port Demo
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_lib.h"
#include "usb_desc.h"
/* USB Standard Device Descriptor */
const uint8_t Virtual_Com_Port_DeviceDescriptor[] = { 0x12, /* bLength */
USB_DEVICE_DESCRIPTOR_TYPE, /* bDescriptorType */
0x00, 0x02, /* bcdUSB = 2.00 */
0x02, /* bDeviceClass: CDC */
0x00, /* bDeviceSubClass */
0x00, /* bDeviceProtocol */
0x40, /* bMaxPacketSize0 */
0x83, 0x04, /* idVendor = 0x0483 */
0x40, 0x57, /* idProduct = 0x7540 */
0x00, 0x02, /* bcdDevice = 2.00 */
1, /* Index of string descriptor describing manufacturer */
2, /* Index of string descriptor describing product */
3, /* Index of string descriptor describing the device's serial number */
0x01 /* bNumConfigurations */
};
const uint8_t Virtual_Com_Port_ConfigDescriptor[] = {
/*Configuration Descriptor*/
0x09, /* bLength: Configuration Descriptor size */
USB_CONFIGURATION_DESCRIPTOR_TYPE, /* bDescriptorType: Configuration */
VIRTUAL_COM_PORT_SIZ_CONFIG_DESC, /* wTotalLength:no of returned bytes */
0x00, 0x02, /* bNumInterfaces: 2 interface */
0x01, /* bConfigurationValue: Configuration value */
0x00, /* iConfiguration: Index of string descriptor describing the configuration */
0xC0, /* bmAttributes: self powered */
0x32, /* MaxPower 0 mA */
/*Interface Descriptor*/
0x09, /* bLength: Interface Descriptor size */
USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType: Interface */
/* Interface descriptor type */
0x00, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x01, /* bNumEndpoints: One endpoints used */
0x02, /* bInterfaceClass: Communication Interface Class */
0x02, /* bInterfaceSubClass: Abstract Control Model */
0x01, /* bInterfaceProtocol: Common AT commands */
0x00, /* iInterface: */
/*Header Functional Descriptor*/
0x05, /* bLength: Endpoint Descriptor size */
0x24, /* bDescriptorType: CS_INTERFACE */
0x00, /* bDescriptorSubtype: Header Func Desc */
0x10, /* bcdCDC: spec release number */
0x01,
/*Call Management Functional Descriptor*/
0x05, /* bFunctionLength */
0x24, /* bDescriptorType: CS_INTERFACE */
0x01, /* bDescriptorSubtype: Call Management Func Desc */
0x00, /* bmCapabilities: D0+D1 */
0x01, /* bDataInterface: 1 */
/*ACM Functional Descriptor*/
0x04, /* bFunctionLength */
0x24, /* bDescriptorType: CS_INTERFACE */
0x02, /* bDescriptorSubtype: Abstract Control Management desc */
0x02, /* bmCapabilities */
/*Union Functional Descriptor*/
0x05, /* bFunctionLength */
0x24, /* bDescriptorType: CS_INTERFACE */
0x06, /* bDescriptorSubtype: Union func desc */
0x00, /* bMasterInterface: Communication class interface */
0x01, /* bSlaveInterface0: Data Class Interface */
/*Endpoint 2 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
0x82, /* bEndpointAddress: (IN2) */
0x03, /* bmAttributes: Interrupt */
VIRTUAL_COM_PORT_INT_SIZE, /* wMaxPacketSize: */
0x00, 0xFF, /* bInterval: */
/*Data class interface descriptor*/
0x09, /* bLength: Endpoint Descriptor size */
USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType: */
0x01, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x02, /* bNumEndpoints: Two endpoints used */
0x0A, /* bInterfaceClass: CDC */
0x00, /* bInterfaceSubClass: */
0x00, /* bInterfaceProtocol: */
0x00, /* iInterface: */
/*Endpoint 3 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
0x03, /* bEndpointAddress: (OUT3) */
0x02, /* bmAttributes: Bulk */
VIRTUAL_COM_PORT_DATA_SIZE, /* wMaxPacketSize: */
0x00, 0x00, /* bInterval: ignore for Bulk transfer */
/*Endpoint 1 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: Endpoint */
0x81, /* bEndpointAddress: (IN1) */
0x02, /* bmAttributes: Bulk */
VIRTUAL_COM_PORT_DATA_SIZE, /* wMaxPacketSize: */
0x00, 0x00 /* bInterval */
};
/* USB String Descriptors */
const uint8_t Virtual_Com_Port_StringLangID[VIRTUAL_COM_PORT_SIZ_STRING_LANGID] = {
VIRTUAL_COM_PORT_SIZ_STRING_LANGID,
USB_STRING_DESCRIPTOR_TYPE, 0x09, 0x04 /* LangID = 0x0409: U.S. English */
};
const uint8_t Virtual_Com_Port_StringVendor[VIRTUAL_COM_PORT_SIZ_STRING_VENDOR] = {
VIRTUAL_COM_PORT_SIZ_STRING_VENDOR, /* Size of Vendor string */
USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType*/
/* Manufacturer: "STMicroelectronics" */
'S', 0, 'T', 0, 'M', 0, 'i', 0, 'c', 0, 'r', 0, 'o', 0, 'e', 0, 'l', 0, 'e', 0, 'c', 0, 't', 0, 'r', 0, 'o', 0, 'n', 0, 'i', 0, 'c', 0, 's', 0 };
const uint8_t Virtual_Com_Port_StringProduct[VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT] = {
VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT, /* bLength */
USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
/* Product name: "STM32 Virtual COM Port" */
'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0, ' ', 0, 'V', 0, 'i', 0, 'r', 0, 't', 0, 'u', 0, 'a', 0, 'l', 0, ' ', 0, 'C', 0, 'O', 0, 'M', 0, ' ', 0, 'P', 0, 'o', 0, 'r', 0, 't', 0, ' ', 0, ' ', 0 };
uint8_t Virtual_Com_Port_StringSerial[VIRTUAL_COM_PORT_SIZ_STRING_SERIAL] = {
VIRTUAL_COM_PORT_SIZ_STRING_SERIAL, /* bLength */
USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0 };
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,65 +1,65 @@
/**
******************************************************************************
* @file usb_desc.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Descriptor Header for Virtual COM Port Device
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_DESC_H
#define __USB_DESC_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported define -----------------------------------------------------------*/
#define USB_DEVICE_DESCRIPTOR_TYPE 0x01
#define USB_CONFIGURATION_DESCRIPTOR_TYPE 0x02
#define USB_STRING_DESCRIPTOR_TYPE 0x03
#define USB_INTERFACE_DESCRIPTOR_TYPE 0x04
#define USB_ENDPOINT_DESCRIPTOR_TYPE 0x05
#define VIRTUAL_COM_PORT_DATA_SIZE 64
#define VIRTUAL_COM_PORT_INT_SIZE 8
#define VIRTUAL_COM_PORT_SIZ_DEVICE_DESC 18
#define VIRTUAL_COM_PORT_SIZ_CONFIG_DESC 67
#define VIRTUAL_COM_PORT_SIZ_STRING_LANGID 4
#define VIRTUAL_COM_PORT_SIZ_STRING_VENDOR 38
#define VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT 50
#define VIRTUAL_COM_PORT_SIZ_STRING_SERIAL 26
#define STANDARD_ENDPOINT_DESC_SIZE 0x09
/* Exported functions ------------------------------------------------------- */
extern const uint8_t Virtual_Com_Port_DeviceDescriptor[VIRTUAL_COM_PORT_SIZ_DEVICE_DESC];
extern const uint8_t Virtual_Com_Port_ConfigDescriptor[VIRTUAL_COM_PORT_SIZ_CONFIG_DESC];
extern const uint8_t Virtual_Com_Port_StringLangID[VIRTUAL_COM_PORT_SIZ_STRING_LANGID];
extern const uint8_t Virtual_Com_Port_StringVendor[VIRTUAL_COM_PORT_SIZ_STRING_VENDOR];
extern const uint8_t Virtual_Com_Port_StringProduct[VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT];
extern uint8_t Virtual_Com_Port_StringSerial[VIRTUAL_COM_PORT_SIZ_STRING_SERIAL];
#endif /* __USB_DESC_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file usb_desc.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Descriptor Header for Virtual COM Port Device
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_DESC_H
#define __USB_DESC_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported define -----------------------------------------------------------*/
#define USB_DEVICE_DESCRIPTOR_TYPE 0x01
#define USB_CONFIGURATION_DESCRIPTOR_TYPE 0x02
#define USB_STRING_DESCRIPTOR_TYPE 0x03
#define USB_INTERFACE_DESCRIPTOR_TYPE 0x04
#define USB_ENDPOINT_DESCRIPTOR_TYPE 0x05
#define VIRTUAL_COM_PORT_DATA_SIZE 64
#define VIRTUAL_COM_PORT_INT_SIZE 8
#define VIRTUAL_COM_PORT_SIZ_DEVICE_DESC 18
#define VIRTUAL_COM_PORT_SIZ_CONFIG_DESC 67
#define VIRTUAL_COM_PORT_SIZ_STRING_LANGID 4
#define VIRTUAL_COM_PORT_SIZ_STRING_VENDOR 38
#define VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT 50
#define VIRTUAL_COM_PORT_SIZ_STRING_SERIAL 26
#define STANDARD_ENDPOINT_DESC_SIZE 0x09
/* Exported functions ------------------------------------------------------- */
extern const uint8_t Virtual_Com_Port_DeviceDescriptor[VIRTUAL_COM_PORT_SIZ_DEVICE_DESC];
extern const uint8_t Virtual_Com_Port_ConfigDescriptor[VIRTUAL_COM_PORT_SIZ_CONFIG_DESC];
extern const uint8_t Virtual_Com_Port_StringLangID[VIRTUAL_COM_PORT_SIZ_STRING_LANGID];
extern const uint8_t Virtual_Com_Port_StringVendor[VIRTUAL_COM_PORT_SIZ_STRING_VENDOR];
extern const uint8_t Virtual_Com_Port_StringProduct[VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT];
extern uint8_t Virtual_Com_Port_StringSerial[VIRTUAL_COM_PORT_SIZ_STRING_SERIAL];
#endif /* __USB_DESC_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,75 +1,75 @@
/**
******************************************************************************
* @file usb_endp.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Endpoint routines
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_lib.h"
#include "usb_desc.h"
#include "usb_mem.h"
#include "hw_config.h"
#include "usb_istr.h"
#include "usb_pwr.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Interval between sending IN packets in frame number (1 frame = 1ms) */
#define VCOMPORT_IN_FRAME_INTERVAL 5
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
extern __IO uint32_t packetSent; // HJI
extern __IO uint8_t receiveBuffer[64]; // HJI
__IO uint32_t receiveLength; // HJI
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : EP1_IN_Callback
* Description :
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void EP1_IN_Callback(void)
{
packetSent = 0; // HJI
}
/*******************************************************************************
* Function Name : EP3_OUT_Callback
* Description :
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void EP3_OUT_Callback(void)
{
receiveLength = GetEPRxCount(ENDP3); // HJI
PMAToUserBufferCopy((unsigned char*)receiveBuffer, ENDP3_RXADDR, receiveLength); // HJI
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file usb_endp.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Endpoint routines
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_lib.h"
#include "usb_desc.h"
#include "usb_mem.h"
#include "hw_config.h"
#include "usb_istr.h"
#include "usb_pwr.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Interval between sending IN packets in frame number (1 frame = 1ms) */
#define VCOMPORT_IN_FRAME_INTERVAL 5
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
extern __IO uint32_t packetSent; // HJI
extern __IO uint8_t receiveBuffer[64]; // HJI
__IO uint32_t receiveLength; // HJI
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : EP1_IN_Callback
* Description :
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void EP1_IN_Callback(void)
{
packetSent = 0; // HJI
}
/*******************************************************************************
* Function Name : EP3_OUT_Callback
* Description :
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void EP3_OUT_Callback(void)
{
receiveLength = GetEPRxCount(ENDP3); // HJI
PMAToUserBufferCopy((unsigned char*)receiveBuffer, ENDP3_RXADDR, receiveLength); // HJI
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,222 +1,222 @@
/**
******************************************************************************
* @file usb_istr.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief ISTR events interrupt service routines
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_lib.h"
#include "usb_prop.h"
#include "usb_pwr.h"
#include "usb_istr.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
__IO uint16_t wIstr; /* ISTR register last read value */
__IO uint8_t bIntPackSOF = 0; /* SOFs received between 2 consecutive packets */
__IO uint32_t esof_counter = 0; /* expected SOF counter */
__IO uint32_t wCNTR = 0;
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* function pointers to non-control endpoints service routines */
void (*pEpInt_IN[7])(void) =
{
EP1_IN_Callback,
EP2_IN_Callback,
EP3_IN_Callback,
EP4_IN_Callback,
EP5_IN_Callback,
EP6_IN_Callback,
EP7_IN_Callback,
};
void (*pEpInt_OUT[7])(void) =
{
EP1_OUT_Callback,
EP2_OUT_Callback,
EP3_OUT_Callback,
EP4_OUT_Callback,
EP5_OUT_Callback,
EP6_OUT_Callback,
EP7_OUT_Callback,
};
/*******************************************************************************
* Function Name : USB_Istr
* Description : ISTR events interrupt service routine
* Input :
* Output :
* Return :
*******************************************************************************/
void USB_Istr(void)
{
wIstr = _GetISTR();
#if (IMR_MSK & ISTR_SOF)
if (wIstr & ISTR_SOF & wInterrupt_Mask) {
_SetISTR((uint16_t)CLR_SOF);
bIntPackSOF++;
#ifdef SOF_CALLBACK
SOF_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_CTR)
if (wIstr & ISTR_CTR & wInterrupt_Mask) {
/* servicing of the endpoint correct transfer interrupt */
/* clear of the CTR flag into the sub */
CTR_LP();
#ifdef CTR_CALLBACK
CTR_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_RESET)
if (wIstr & ISTR_RESET & wInterrupt_Mask) {
_SetISTR((uint16_t)CLR_RESET);
Device_Property.Reset();
#ifdef RESET_CALLBACK
RESET_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_DOVR)
if (wIstr & ISTR_DOVR & wInterrupt_Mask)
{
_SetISTR((uint16_t)CLR_DOVR);
#ifdef DOVR_CALLBACK
DOVR_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_ERR)
if (wIstr & ISTR_ERR & wInterrupt_Mask) {
_SetISTR((uint16_t)CLR_ERR);
#ifdef ERR_CALLBACK
ERR_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_WKUP)
if (wIstr & ISTR_WKUP & wInterrupt_Mask) {
_SetISTR((uint16_t)CLR_WKUP);
Resume(RESUME_EXTERNAL);
#ifdef WKUP_CALLBACK
WKUP_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_SUSP)
if (wIstr & ISTR_SUSP & wInterrupt_Mask)
{
/* check if SUSPEND is possible */
if (fSuspendEnabled)
{
Suspend();
}
else
{
/* if not possible then resume after xx ms */
Resume(RESUME_LATER);
}
/* clear of the ISTR bit must be done after setting of CNTR_FSUSP */
_SetISTR((uint16_t)CLR_SUSP);
#ifdef SUSP_CALLBACK
SUSP_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_ESOF)
if (wIstr & ISTR_ESOF & wInterrupt_Mask)
{
/* clear ESOF flag in ISTR */
_SetISTR((uint16_t)CLR_ESOF);
if ((_GetFNR()&FNR_RXDP)!=0)
{
/* increment ESOF counter */
esof_counter ++;
/* test if we enter in ESOF more than 3 times with FSUSP =0 and RXDP =1=>> possible missing SUSP flag*/
if ((esof_counter >3)&&((_GetCNTR()&CNTR_FSUSP)==0))
{
/* this a sequence to apply a force RESET*/
/*Store CNTR value */
wCNTR = _GetCNTR();
/*Store endpoints registers status */
for (i=0;i<8;i++) EP[i] = _GetENDPOINT(i);
/*apply FRES */
wCNTR|=CNTR_FRES;
_SetCNTR(wCNTR);
/*clear FRES*/
wCNTR&=~CNTR_FRES;
_SetCNTR(wCNTR);
/*poll for RESET flag in ISTR*/
while((_GetISTR()&ISTR_RESET) == 0);
/* clear RESET flag in ISTR */
_SetISTR((uint16_t)CLR_RESET);
/*restore Enpoints*/
for (i=0;i<8;i++)
_SetENDPOINT(i, EP[i]);
esof_counter = 0;
}
}
else
{
esof_counter = 0;
}
/* resume handling timing is made with ESOFs */
Resume(RESUME_ESOF); /* request without change of the machine state */
#ifdef ESOF_CALLBACK
ESOF_Callback();
#endif
}
#endif
} /* USB_Istr */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file usb_istr.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief ISTR events interrupt service routines
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_lib.h"
#include "usb_prop.h"
#include "usb_pwr.h"
#include "usb_istr.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
__IO uint16_t wIstr; /* ISTR register last read value */
__IO uint8_t bIntPackSOF = 0; /* SOFs received between 2 consecutive packets */
__IO uint32_t esof_counter = 0; /* expected SOF counter */
__IO uint32_t wCNTR = 0;
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* function pointers to non-control endpoints service routines */
void (*pEpInt_IN[7])(void) =
{
EP1_IN_Callback,
EP2_IN_Callback,
EP3_IN_Callback,
EP4_IN_Callback,
EP5_IN_Callback,
EP6_IN_Callback,
EP7_IN_Callback,
};
void (*pEpInt_OUT[7])(void) =
{
EP1_OUT_Callback,
EP2_OUT_Callback,
EP3_OUT_Callback,
EP4_OUT_Callback,
EP5_OUT_Callback,
EP6_OUT_Callback,
EP7_OUT_Callback,
};
/*******************************************************************************
* Function Name : USB_Istr
* Description : ISTR events interrupt service routine
* Input :
* Output :
* Return :
*******************************************************************************/
void USB_Istr(void)
{
wIstr = _GetISTR();
#if (IMR_MSK & ISTR_SOF)
if (wIstr & ISTR_SOF & wInterrupt_Mask) {
_SetISTR((uint16_t)CLR_SOF);
bIntPackSOF++;
#ifdef SOF_CALLBACK
SOF_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_CTR)
if (wIstr & ISTR_CTR & wInterrupt_Mask) {
/* servicing of the endpoint correct transfer interrupt */
/* clear of the CTR flag into the sub */
CTR_LP();
#ifdef CTR_CALLBACK
CTR_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_RESET)
if (wIstr & ISTR_RESET & wInterrupt_Mask) {
_SetISTR((uint16_t)CLR_RESET);
Device_Property.Reset();
#ifdef RESET_CALLBACK
RESET_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_DOVR)
if (wIstr & ISTR_DOVR & wInterrupt_Mask)
{
_SetISTR((uint16_t)CLR_DOVR);
#ifdef DOVR_CALLBACK
DOVR_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_ERR)
if (wIstr & ISTR_ERR & wInterrupt_Mask) {
_SetISTR((uint16_t)CLR_ERR);
#ifdef ERR_CALLBACK
ERR_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_WKUP)
if (wIstr & ISTR_WKUP & wInterrupt_Mask) {
_SetISTR((uint16_t)CLR_WKUP);
Resume(RESUME_EXTERNAL);
#ifdef WKUP_CALLBACK
WKUP_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_SUSP)
if (wIstr & ISTR_SUSP & wInterrupt_Mask)
{
/* check if SUSPEND is possible */
if (fSuspendEnabled)
{
Suspend();
}
else
{
/* if not possible then resume after xx ms */
Resume(RESUME_LATER);
}
/* clear of the ISTR bit must be done after setting of CNTR_FSUSP */
_SetISTR((uint16_t)CLR_SUSP);
#ifdef SUSP_CALLBACK
SUSP_Callback();
#endif
}
#endif
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
#if (IMR_MSK & ISTR_ESOF)
if (wIstr & ISTR_ESOF & wInterrupt_Mask)
{
/* clear ESOF flag in ISTR */
_SetISTR((uint16_t)CLR_ESOF);
if ((_GetFNR()&FNR_RXDP)!=0)
{
/* increment ESOF counter */
esof_counter ++;
/* test if we enter in ESOF more than 3 times with FSUSP =0 and RXDP =1=>> possible missing SUSP flag*/
if ((esof_counter >3)&&((_GetCNTR()&CNTR_FSUSP)==0))
{
/* this a sequence to apply a force RESET*/
/*Store CNTR value */
wCNTR = _GetCNTR();
/*Store endpoints registers status */
for (i=0;i<8;i++) EP[i] = _GetENDPOINT(i);
/*apply FRES */
wCNTR|=CNTR_FRES;
_SetCNTR(wCNTR);
/*clear FRES*/
wCNTR&=~CNTR_FRES;
_SetCNTR(wCNTR);
/*poll for RESET flag in ISTR*/
while((_GetISTR()&ISTR_RESET) == 0);
/* clear RESET flag in ISTR */
_SetISTR((uint16_t)CLR_RESET);
/*restore Enpoints*/
for (i=0;i<8;i++)
_SetENDPOINT(i, EP[i]);
esof_counter = 0;
}
}
else
{
esof_counter = 0;
}
/* resume handling timing is made with ESOFs */
Resume(RESUME_ESOF); /* request without change of the machine state */
#ifdef ESOF_CALLBACK
ESOF_Callback();
#endif
}
#endif
} /* USB_Istr */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,93 +1,93 @@
/**
******************************************************************************
* @file usb_istr.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief This file includes the peripherals header files in the user application.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_ISTR_H
#define __USB_ISTR_H
/* Includes ------------------------------------------------------------------*/
#include "usb_conf.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void USB_Istr(void);
/* function prototypes Automatically built defining related macros */
void EP1_IN_Callback(void);
void EP2_IN_Callback(void);
void EP3_IN_Callback(void);
void EP4_IN_Callback(void);
void EP5_IN_Callback(void);
void EP6_IN_Callback(void);
void EP7_IN_Callback(void);
void EP1_OUT_Callback(void);
void EP2_OUT_Callback(void);
void EP3_OUT_Callback(void);
void EP4_OUT_Callback(void);
void EP5_OUT_Callback(void);
void EP6_OUT_Callback(void);
void EP7_OUT_Callback(void);
#ifdef CTR_CALLBACK
void CTR_Callback(void);
#endif
#ifdef DOVR_CALLBACK
void DOVR_Callback(void);
#endif
#ifdef ERR_CALLBACK
void ERR_Callback(void);
#endif
#ifdef WKUP_CALLBACK
void WKUP_Callback(void);
#endif
#ifdef SUSP_CALLBACK
void SUSP_Callback(void);
#endif
#ifdef RESET_CALLBACK
void RESET_Callback(void);
#endif
#ifdef SOF_CALLBACK
void SOF_Callback(void);
#endif
#ifdef ESOF_CALLBACK
void ESOF_Callback(void);
#endif
#endif /*__USB_ISTR_H*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file usb_istr.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief This file includes the peripherals header files in the user application.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_ISTR_H
#define __USB_ISTR_H
/* Includes ------------------------------------------------------------------*/
#include "usb_conf.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void USB_Istr(void);
/* function prototypes Automatically built defining related macros */
void EP1_IN_Callback(void);
void EP2_IN_Callback(void);
void EP3_IN_Callback(void);
void EP4_IN_Callback(void);
void EP5_IN_Callback(void);
void EP6_IN_Callback(void);
void EP7_IN_Callback(void);
void EP1_OUT_Callback(void);
void EP2_OUT_Callback(void);
void EP3_OUT_Callback(void);
void EP4_OUT_Callback(void);
void EP5_OUT_Callback(void);
void EP6_OUT_Callback(void);
void EP7_OUT_Callback(void);
#ifdef CTR_CALLBACK
void CTR_Callback(void);
#endif
#ifdef DOVR_CALLBACK
void DOVR_Callback(void);
#endif
#ifdef ERR_CALLBACK
void ERR_Callback(void);
#endif
#ifdef WKUP_CALLBACK
void WKUP_Callback(void);
#endif
#ifdef SUSP_CALLBACK
void SUSP_Callback(void);
#endif
#ifdef RESET_CALLBACK
void RESET_Callback(void);
#endif
#ifdef SOF_CALLBACK
void SOF_Callback(void);
#endif
#ifdef ESOF_CALLBACK
void ESOF_Callback(void);
#endif
#endif /*__USB_ISTR_H*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,362 +1,362 @@
/**
******************************************************************************
* @file usb_prop.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief All processing related to Virtual Com Port Demo
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_lib.h"
#include "usb_conf.h"
#include "usb_prop.h"
#include "usb_desc.h"
#include "usb_pwr.h"
#include "hw_config.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
uint8_t Request = 0;
LINE_CODING linecoding = { 115200, /* baud rate*/
0x00, /* stop bits-1*/
0x00, /* parity - none*/
0x08 /* no. of bits 8*/
};
/* -------------------------------------------------------------------------- */
/* Structures initializations */
/* -------------------------------------------------------------------------- */
DEVICE Device_Table = {
EP_NUM, 1 };
DEVICE_PROP Device_Property = { Virtual_Com_Port_init, Virtual_Com_Port_Reset, Virtual_Com_Port_Status_In, Virtual_Com_Port_Status_Out, Virtual_Com_Port_Data_Setup, Virtual_Com_Port_NoData_Setup, Virtual_Com_Port_Get_Interface_Setting, Virtual_Com_Port_GetDeviceDescriptor,
Virtual_Com_Port_GetConfigDescriptor, Virtual_Com_Port_GetStringDescriptor, 0, 0x40 /*MAX PACKET SIZE*/
};
USER_STANDARD_REQUESTS User_Standard_Requests = {
Virtual_Com_Port_GetConfiguration, Virtual_Com_Port_SetConfiguration,
Virtual_Com_Port_GetInterface,
Virtual_Com_Port_SetInterface,
Virtual_Com_Port_GetStatus,
Virtual_Com_Port_ClearFeature,
Virtual_Com_Port_SetEndPointFeature,
Virtual_Com_Port_SetDeviceFeature, Virtual_Com_Port_SetDeviceAddress };
ONE_DESCRIPTOR Device_Descriptor = { (uint8_t*)Virtual_Com_Port_DeviceDescriptor,
VIRTUAL_COM_PORT_SIZ_DEVICE_DESC };
ONE_DESCRIPTOR Config_Descriptor = { (uint8_t*)Virtual_Com_Port_ConfigDescriptor,
VIRTUAL_COM_PORT_SIZ_CONFIG_DESC };
ONE_DESCRIPTOR String_Descriptor[4] = { { (uint8_t*)Virtual_Com_Port_StringLangID, VIRTUAL_COM_PORT_SIZ_STRING_LANGID }, { (uint8_t*)Virtual_Com_Port_StringVendor, VIRTUAL_COM_PORT_SIZ_STRING_VENDOR }, { (uint8_t*)Virtual_Com_Port_StringProduct,
VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT }, { (uint8_t*)Virtual_Com_Port_StringSerial, VIRTUAL_COM_PORT_SIZ_STRING_SERIAL } };
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Extern function prototypes ------------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : Virtual_Com_Port_init.
* Description : Virtual COM Port Mouse init routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_init(void)
{
/* Update the serial number string descriptor with the data from the unique
ID*/
Get_SerialNum();
pInformation->Current_Configuration = 0;
/* Connect the device */
PowerOn();
/* Perform basic device initialization operations */
USB_SIL_Init();
bDeviceState = UNCONNECTED;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_Reset
* Description : Virtual_Com_Port Mouse reset routine
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_Reset(void)
{
/* Set Virtual_Com_Port DEVICE as not configured */
pInformation->Current_Configuration = 0;
/* Current Feature initialization */
pInformation->Current_Feature = Virtual_Com_Port_ConfigDescriptor[7];
/* Set Virtual_Com_Port DEVICE with the default Interface*/
pInformation->Current_Interface = 0;
SetBTABLE(BTABLE_ADDRESS);
/* Initialize Endpoint 0 */
SetEPType(ENDP0, EP_CONTROL);
SetEPTxStatus(ENDP0, EP_TX_STALL);
SetEPRxAddr(ENDP0, ENDP0_RXADDR);
SetEPTxAddr(ENDP0, ENDP0_TXADDR);
Clear_Status_Out(ENDP0);
SetEPRxCount(ENDP0, Device_Property.MaxPacketSize);
SetEPRxValid(ENDP0);
/* Initialize Endpoint 1 */
SetEPType(ENDP1, EP_BULK);
SetEPTxAddr(ENDP1, ENDP1_TXADDR);
SetEPTxStatus(ENDP1, EP_TX_NAK);
SetEPRxStatus(ENDP1, EP_RX_DIS);
/* Initialize Endpoint 2 */
SetEPType(ENDP2, EP_INTERRUPT);
SetEPTxAddr(ENDP2, ENDP2_TXADDR);
SetEPRxStatus(ENDP2, EP_RX_DIS);
SetEPTxStatus(ENDP2, EP_TX_NAK);
/* Initialize Endpoint 3 */
SetEPType(ENDP3, EP_BULK);
SetEPRxAddr(ENDP3, ENDP3_RXADDR);
SetEPRxCount(ENDP3, VIRTUAL_COM_PORT_DATA_SIZE);
SetEPRxStatus(ENDP3, EP_RX_VALID);
SetEPTxStatus(ENDP3, EP_TX_DIS);
/* Set this device to response on default address */
SetDeviceAddress(0);
bDeviceState = ATTACHED;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_SetConfiguration.
* Description : Update the device state to configured.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_SetConfiguration(void)
{
DEVICE_INFO *pInfo = &Device_Info;
if (pInfo->Current_Configuration != 0) {
/* Device configured */
bDeviceState = CONFIGURED;
}
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_SetConfiguration.
* Description : Update the device state to addressed.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_SetDeviceAddress(void)
{
bDeviceState = ADDRESSED;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_Status_In.
* Description : Virtual COM Port Status In Routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_Status_In(void)
{
if (Request == SET_LINE_CODING) {
Request = 0;
}
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_Status_Out
* Description : Virtual COM Port Status OUT Routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_Status_Out(void)
{
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_Data_Setup
* Description : handle the data class specific requests
* Input : Request Nb.
* Output : None.
* Return : USB_UNSUPPORT or USB_SUCCESS.
*******************************************************************************/
RESULT Virtual_Com_Port_Data_Setup(uint8_t RequestNo)
{
uint8_t *(*CopyRoutine)( uint16_t);
CopyRoutine = NULL;
if (RequestNo == GET_LINE_CODING) {
if (Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) {
CopyRoutine = Virtual_Com_Port_GetLineCoding;
}
} else if (RequestNo == SET_LINE_CODING) {
if (Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) {
CopyRoutine = Virtual_Com_Port_SetLineCoding;
}
Request = SET_LINE_CODING;
}
if (CopyRoutine == NULL) {
return USB_UNSUPPORT;
}
pInformation->Ctrl_Info.CopyData = CopyRoutine;
pInformation->Ctrl_Info.Usb_wOffset = 0;
(*CopyRoutine)(0);
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_NoData_Setup.
* Description : handle the no data class specific requests.
* Input : Request Nb.
* Output : None.
* Return : USB_UNSUPPORT or USB_SUCCESS.
*******************************************************************************/
RESULT Virtual_Com_Port_NoData_Setup(uint8_t RequestNo)
{
if (Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) {
if (RequestNo == SET_COMM_FEATURE) {
return USB_SUCCESS;
} else if (RequestNo == SET_CONTROL_LINE_STATE) {
return USB_SUCCESS;
}
}
return USB_UNSUPPORT;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_GetDeviceDescriptor.
* Description : Gets the device descriptor.
* Input : Length.
* Output : None.
* Return : The address of the device descriptor.
*******************************************************************************/
uint8_t *Virtual_Com_Port_GetDeviceDescriptor(uint16_t Length)
{
return Standard_GetDescriptorData(Length, &Device_Descriptor);
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_GetConfigDescriptor.
* Description : get the configuration descriptor.
* Input : Length.
* Output : None.
* Return : The address of the configuration descriptor.
*******************************************************************************/
uint8_t *Virtual_Com_Port_GetConfigDescriptor(uint16_t Length)
{
return Standard_GetDescriptorData(Length, &Config_Descriptor);
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_GetStringDescriptor
* Description : Gets the string descriptors according to the needed index
* Input : Length.
* Output : None.
* Return : The address of the string descriptors.
*******************************************************************************/
uint8_t *Virtual_Com_Port_GetStringDescriptor(uint16_t Length)
{
uint8_t wValue0 = pInformation->USBwValue0;
if (wValue0 > 4) {
return NULL;
} else {
return Standard_GetDescriptorData(Length, &String_Descriptor[wValue0]);
}
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_Get_Interface_Setting.
* Description : test the interface and the alternate setting according to the
* supported one.
* Input1 : uint8_t: Interface : interface number.
* Input2 : uint8_t: AlternateSetting : Alternate Setting number.
* Output : None.
* Return : The address of the string descriptors.
*******************************************************************************/
RESULT Virtual_Com_Port_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting)
{
if (AlternateSetting > 0) {
return USB_UNSUPPORT;
} else if (Interface > 1) {
return USB_UNSUPPORT;
}
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_GetLineCoding.
* Description : send the linecoding structure to the PC host.
* Input : Length.
* Output : None.
* Return : Linecoding structure base address.
*******************************************************************************/
uint8_t *Virtual_Com_Port_GetLineCoding(uint16_t Length)
{
if (Length == 0) {
pInformation->Ctrl_Info.Usb_wLength = sizeof(linecoding);
return NULL;
}
return (uint8_t *)&linecoding;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_SetLineCoding.
* Description : Set the linecoding structure fields.
* Input : Length.
* Output : None.
* Return : Linecoding structure base address.
*******************************************************************************/
uint8_t *Virtual_Com_Port_SetLineCoding(uint16_t Length)
{
if (Length == 0) {
pInformation->Ctrl_Info.Usb_wLength = sizeof(linecoding);
return NULL;
}
return (uint8_t *)&linecoding;
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file usb_prop.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief All processing related to Virtual Com Port Demo
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_lib.h"
#include "usb_conf.h"
#include "usb_prop.h"
#include "usb_desc.h"
#include "usb_pwr.h"
#include "hw_config.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
uint8_t Request = 0;
LINE_CODING linecoding = { 115200, /* baud rate*/
0x00, /* stop bits-1*/
0x00, /* parity - none*/
0x08 /* no. of bits 8*/
};
/* -------------------------------------------------------------------------- */
/* Structures initializations */
/* -------------------------------------------------------------------------- */
DEVICE Device_Table = {
EP_NUM, 1 };
DEVICE_PROP Device_Property = { Virtual_Com_Port_init, Virtual_Com_Port_Reset, Virtual_Com_Port_Status_In, Virtual_Com_Port_Status_Out, Virtual_Com_Port_Data_Setup, Virtual_Com_Port_NoData_Setup, Virtual_Com_Port_Get_Interface_Setting, Virtual_Com_Port_GetDeviceDescriptor,
Virtual_Com_Port_GetConfigDescriptor, Virtual_Com_Port_GetStringDescriptor, 0, 0x40 /*MAX PACKET SIZE*/
};
USER_STANDARD_REQUESTS User_Standard_Requests = {
Virtual_Com_Port_GetConfiguration, Virtual_Com_Port_SetConfiguration,
Virtual_Com_Port_GetInterface,
Virtual_Com_Port_SetInterface,
Virtual_Com_Port_GetStatus,
Virtual_Com_Port_ClearFeature,
Virtual_Com_Port_SetEndPointFeature,
Virtual_Com_Port_SetDeviceFeature, Virtual_Com_Port_SetDeviceAddress };
ONE_DESCRIPTOR Device_Descriptor = { (uint8_t*)Virtual_Com_Port_DeviceDescriptor,
VIRTUAL_COM_PORT_SIZ_DEVICE_DESC };
ONE_DESCRIPTOR Config_Descriptor = { (uint8_t*)Virtual_Com_Port_ConfigDescriptor,
VIRTUAL_COM_PORT_SIZ_CONFIG_DESC };
ONE_DESCRIPTOR String_Descriptor[4] = { { (uint8_t*)Virtual_Com_Port_StringLangID, VIRTUAL_COM_PORT_SIZ_STRING_LANGID }, { (uint8_t*)Virtual_Com_Port_StringVendor, VIRTUAL_COM_PORT_SIZ_STRING_VENDOR }, { (uint8_t*)Virtual_Com_Port_StringProduct,
VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT }, { (uint8_t*)Virtual_Com_Port_StringSerial, VIRTUAL_COM_PORT_SIZ_STRING_SERIAL } };
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Extern function prototypes ------------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : Virtual_Com_Port_init.
* Description : Virtual COM Port Mouse init routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_init(void)
{
/* Update the serial number string descriptor with the data from the unique
ID*/
Get_SerialNum();
pInformation->Current_Configuration = 0;
/* Connect the device */
PowerOn();
/* Perform basic device initialization operations */
USB_SIL_Init();
bDeviceState = UNCONNECTED;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_Reset
* Description : Virtual_Com_Port Mouse reset routine
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_Reset(void)
{
/* Set Virtual_Com_Port DEVICE as not configured */
pInformation->Current_Configuration = 0;
/* Current Feature initialization */
pInformation->Current_Feature = Virtual_Com_Port_ConfigDescriptor[7];
/* Set Virtual_Com_Port DEVICE with the default Interface*/
pInformation->Current_Interface = 0;
SetBTABLE(BTABLE_ADDRESS);
/* Initialize Endpoint 0 */
SetEPType(ENDP0, EP_CONTROL);
SetEPTxStatus(ENDP0, EP_TX_STALL);
SetEPRxAddr(ENDP0, ENDP0_RXADDR);
SetEPTxAddr(ENDP0, ENDP0_TXADDR);
Clear_Status_Out(ENDP0);
SetEPRxCount(ENDP0, Device_Property.MaxPacketSize);
SetEPRxValid(ENDP0);
/* Initialize Endpoint 1 */
SetEPType(ENDP1, EP_BULK);
SetEPTxAddr(ENDP1, ENDP1_TXADDR);
SetEPTxStatus(ENDP1, EP_TX_NAK);
SetEPRxStatus(ENDP1, EP_RX_DIS);
/* Initialize Endpoint 2 */
SetEPType(ENDP2, EP_INTERRUPT);
SetEPTxAddr(ENDP2, ENDP2_TXADDR);
SetEPRxStatus(ENDP2, EP_RX_DIS);
SetEPTxStatus(ENDP2, EP_TX_NAK);
/* Initialize Endpoint 3 */
SetEPType(ENDP3, EP_BULK);
SetEPRxAddr(ENDP3, ENDP3_RXADDR);
SetEPRxCount(ENDP3, VIRTUAL_COM_PORT_DATA_SIZE);
SetEPRxStatus(ENDP3, EP_RX_VALID);
SetEPTxStatus(ENDP3, EP_TX_DIS);
/* Set this device to response on default address */
SetDeviceAddress(0);
bDeviceState = ATTACHED;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_SetConfiguration.
* Description : Update the device state to configured.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_SetConfiguration(void)
{
DEVICE_INFO *pInfo = &Device_Info;
if (pInfo->Current_Configuration != 0) {
/* Device configured */
bDeviceState = CONFIGURED;
}
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_SetConfiguration.
* Description : Update the device state to addressed.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_SetDeviceAddress(void)
{
bDeviceState = ADDRESSED;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_Status_In.
* Description : Virtual COM Port Status In Routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_Status_In(void)
{
if (Request == SET_LINE_CODING) {
Request = 0;
}
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_Status_Out
* Description : Virtual COM Port Status OUT Routine.
* Input : None.
* Output : None.
* Return : None.
*******************************************************************************/
void Virtual_Com_Port_Status_Out(void)
{
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_Data_Setup
* Description : handle the data class specific requests
* Input : Request Nb.
* Output : None.
* Return : USB_UNSUPPORT or USB_SUCCESS.
*******************************************************************************/
RESULT Virtual_Com_Port_Data_Setup(uint8_t RequestNo)
{
uint8_t *(*CopyRoutine)( uint16_t);
CopyRoutine = NULL;
if (RequestNo == GET_LINE_CODING) {
if (Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) {
CopyRoutine = Virtual_Com_Port_GetLineCoding;
}
} else if (RequestNo == SET_LINE_CODING) {
if (Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) {
CopyRoutine = Virtual_Com_Port_SetLineCoding;
}
Request = SET_LINE_CODING;
}
if (CopyRoutine == NULL) {
return USB_UNSUPPORT;
}
pInformation->Ctrl_Info.CopyData = CopyRoutine;
pInformation->Ctrl_Info.Usb_wOffset = 0;
(*CopyRoutine)(0);
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_NoData_Setup.
* Description : handle the no data class specific requests.
* Input : Request Nb.
* Output : None.
* Return : USB_UNSUPPORT or USB_SUCCESS.
*******************************************************************************/
RESULT Virtual_Com_Port_NoData_Setup(uint8_t RequestNo)
{
if (Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) {
if (RequestNo == SET_COMM_FEATURE) {
return USB_SUCCESS;
} else if (RequestNo == SET_CONTROL_LINE_STATE) {
return USB_SUCCESS;
}
}
return USB_UNSUPPORT;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_GetDeviceDescriptor.
* Description : Gets the device descriptor.
* Input : Length.
* Output : None.
* Return : The address of the device descriptor.
*******************************************************************************/
uint8_t *Virtual_Com_Port_GetDeviceDescriptor(uint16_t Length)
{
return Standard_GetDescriptorData(Length, &Device_Descriptor);
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_GetConfigDescriptor.
* Description : get the configuration descriptor.
* Input : Length.
* Output : None.
* Return : The address of the configuration descriptor.
*******************************************************************************/
uint8_t *Virtual_Com_Port_GetConfigDescriptor(uint16_t Length)
{
return Standard_GetDescriptorData(Length, &Config_Descriptor);
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_GetStringDescriptor
* Description : Gets the string descriptors according to the needed index
* Input : Length.
* Output : None.
* Return : The address of the string descriptors.
*******************************************************************************/
uint8_t *Virtual_Com_Port_GetStringDescriptor(uint16_t Length)
{
uint8_t wValue0 = pInformation->USBwValue0;
if (wValue0 > 4) {
return NULL;
} else {
return Standard_GetDescriptorData(Length, &String_Descriptor[wValue0]);
}
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_Get_Interface_Setting.
* Description : test the interface and the alternate setting according to the
* supported one.
* Input1 : uint8_t: Interface : interface number.
* Input2 : uint8_t: AlternateSetting : Alternate Setting number.
* Output : None.
* Return : The address of the string descriptors.
*******************************************************************************/
RESULT Virtual_Com_Port_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting)
{
if (AlternateSetting > 0) {
return USB_UNSUPPORT;
} else if (Interface > 1) {
return USB_UNSUPPORT;
}
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_GetLineCoding.
* Description : send the linecoding structure to the PC host.
* Input : Length.
* Output : None.
* Return : Linecoding structure base address.
*******************************************************************************/
uint8_t *Virtual_Com_Port_GetLineCoding(uint16_t Length)
{
if (Length == 0) {
pInformation->Ctrl_Info.Usb_wLength = sizeof(linecoding);
return NULL;
}
return (uint8_t *)&linecoding;
}
/*******************************************************************************
* Function Name : Virtual_Com_Port_SetLineCoding.
* Description : Set the linecoding structure fields.
* Input : Length.
* Output : None.
* Return : Linecoding structure base address.
*******************************************************************************/
uint8_t *Virtual_Com_Port_SetLineCoding(uint16_t Length)
{
if (Length == 0) {
pInformation->Ctrl_Info.Usb_wLength = sizeof(linecoding);
return NULL;
}
return (uint8_t *)&linecoding;
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,85 +1,85 @@
/**
******************************************************************************
* @file usb_prop.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief All processing related to Virtual COM Port Demo (Endpoint 0)
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __usb_prop_H
#define __usb_prop_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef struct {
uint32_t bitrate;
uint8_t format;
uint8_t paritytype;
uint8_t datatype;
} LINE_CODING;
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported define -----------------------------------------------------------*/
#define Virtual_Com_Port_GetConfiguration NOP_Process
//#define Virtual_Com_Port_SetConfiguration NOP_Process
#define Virtual_Com_Port_GetInterface NOP_Process
#define Virtual_Com_Port_SetInterface NOP_Process
#define Virtual_Com_Port_GetStatus NOP_Process
#define Virtual_Com_Port_ClearFeature NOP_Process
#define Virtual_Com_Port_SetEndPointFeature NOP_Process
#define Virtual_Com_Port_SetDeviceFeature NOP_Process
//#define Virtual_Com_Port_SetDeviceAddress NOP_Process
#define SEND_ENCAPSULATED_COMMAND 0x00
#define GET_ENCAPSULATED_RESPONSE 0x01
#define SET_COMM_FEATURE 0x02
#define GET_COMM_FEATURE 0x03
#define CLEAR_COMM_FEATURE 0x04
#define SET_LINE_CODING 0x20
#define GET_LINE_CODING 0x21
#define SET_CONTROL_LINE_STATE 0x22
#define SEND_BREAK 0x23
/* Exported functions ------------------------------------------------------- */
void Virtual_Com_Port_init(void);
void Virtual_Com_Port_Reset(void);
void Virtual_Com_Port_SetConfiguration(void);
void Virtual_Com_Port_SetDeviceAddress(void);
void Virtual_Com_Port_Status_In(void);
void Virtual_Com_Port_Status_Out(void);
RESULT Virtual_Com_Port_Data_Setup( uint8_t);
RESULT Virtual_Com_Port_NoData_Setup( uint8_t);
RESULT Virtual_Com_Port_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting);
uint8_t *Virtual_Com_Port_GetDeviceDescriptor( uint16_t);
uint8_t *Virtual_Com_Port_GetConfigDescriptor( uint16_t);
uint8_t *Virtual_Com_Port_GetStringDescriptor( uint16_t);
uint8_t *Virtual_Com_Port_GetLineCoding(uint16_t Length);
uint8_t *Virtual_Com_Port_SetLineCoding(uint16_t Length);
#endif /* __usb_prop_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file usb_prop.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief All processing related to Virtual COM Port Demo (Endpoint 0)
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __usb_prop_H
#define __usb_prop_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef struct {
uint32_t bitrate;
uint8_t format;
uint8_t paritytype;
uint8_t datatype;
} LINE_CODING;
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported define -----------------------------------------------------------*/
#define Virtual_Com_Port_GetConfiguration NOP_Process
//#define Virtual_Com_Port_SetConfiguration NOP_Process
#define Virtual_Com_Port_GetInterface NOP_Process
#define Virtual_Com_Port_SetInterface NOP_Process
#define Virtual_Com_Port_GetStatus NOP_Process
#define Virtual_Com_Port_ClearFeature NOP_Process
#define Virtual_Com_Port_SetEndPointFeature NOP_Process
#define Virtual_Com_Port_SetDeviceFeature NOP_Process
//#define Virtual_Com_Port_SetDeviceAddress NOP_Process
#define SEND_ENCAPSULATED_COMMAND 0x00
#define GET_ENCAPSULATED_RESPONSE 0x01
#define SET_COMM_FEATURE 0x02
#define GET_COMM_FEATURE 0x03
#define CLEAR_COMM_FEATURE 0x04
#define SET_LINE_CODING 0x20
#define GET_LINE_CODING 0x21
#define SET_CONTROL_LINE_STATE 0x22
#define SEND_BREAK 0x23
/* Exported functions ------------------------------------------------------- */
void Virtual_Com_Port_init(void);
void Virtual_Com_Port_Reset(void);
void Virtual_Com_Port_SetConfiguration(void);
void Virtual_Com_Port_SetDeviceAddress(void);
void Virtual_Com_Port_Status_In(void);
void Virtual_Com_Port_Status_Out(void);
RESULT Virtual_Com_Port_Data_Setup( uint8_t);
RESULT Virtual_Com_Port_NoData_Setup( uint8_t);
RESULT Virtual_Com_Port_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting);
uint8_t *Virtual_Com_Port_GetDeviceDescriptor( uint16_t);
uint8_t *Virtual_Com_Port_GetConfigDescriptor( uint16_t);
uint8_t *Virtual_Com_Port_GetStringDescriptor( uint16_t);
uint8_t *Virtual_Com_Port_GetLineCoding(uint16_t Length);
uint8_t *Virtual_Com_Port_SetLineCoding(uint16_t Length);
#endif /* __usb_prop_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,310 +1,310 @@
/**
******************************************************************************
* @file usb_pwr.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Connection/disconnection & power management
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_lib.h"
#include "usb_conf.h"
#include "usb_pwr.h"
#include "hw_config.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
__IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */
__IO boolean fSuspendEnabled = TRUE; /* true when suspend is possible */ // HJI
__IO uint32_t EP[8];
struct {
__IO RESUME_STATE eState;
__IO uint8_t bESOFcnt;
} ResumeS;
__IO uint32_t remotewakeupon = 0;
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Extern function prototypes ------------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : PowerOn
* Description :
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
RESULT PowerOn(void)
{
uint16_t wRegVal;
/*** cable plugged-in ? ***/
USB_Cable_Config(ENABLE);
/*** CNTR_PWDN = 0 ***/
wRegVal = CNTR_FRES;
_SetCNTR(wRegVal);
/*** CNTR_FRES = 0 ***/
wInterrupt_Mask = 0;
_SetCNTR(wInterrupt_Mask);
/*** Clear pending interrupts ***/
_SetISTR(0);
/*** Set interrupt mask ***/
wInterrupt_Mask = CNTR_RESETM | CNTR_SUSPM | CNTR_WKUPM;
_SetCNTR(wInterrupt_Mask);
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : PowerOff
* Description : handles switch-off conditions
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
RESULT PowerOff()
{
/* disable all interrupts and force USB reset */
_SetCNTR(CNTR_FRES);
/* clear interrupt status register */
_SetISTR(0);
/* Disable the Pull-Up*/
USB_Cable_Config(DISABLE);
/* switch-off device */
_SetCNTR(CNTR_FRES + CNTR_PDWN);
/* sw variables reset */
/* ... */
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : Suspend
* Description : sets suspend mode operating conditions
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
void Suspend(void)
{
uint32_t i = 0;
uint16_t wCNTR;
uint32_t tmpreg = 0;
__IO uint32_t savePWR_CR = 0;
/* suspend preparation */
/* ... */
/*Store CNTR value */
wCNTR = _GetCNTR();
/* This a sequence to apply a force RESET to handle a robustness case */
/*Store endpoints registers status */
for (i = 0; i < 8; i++)
EP[i] = _GetENDPOINT(i);
/* unmask RESET flag */
wCNTR |= CNTR_RESETM;
_SetCNTR(wCNTR);
/*apply FRES */
wCNTR |= CNTR_FRES;
_SetCNTR(wCNTR);
/*clear FRES*/
wCNTR &= ~CNTR_FRES;
_SetCNTR(wCNTR);
/*poll for RESET flag in ISTR*/
while ((_GetISTR() & ISTR_RESET) == 0)
;
/* clear RESET flag in ISTR */
_SetISTR((uint16_t)CLR_RESET);
/*restore Enpoints*/
for (i = 0; i < 8; i++)
_SetENDPOINT(i, EP[i]);
/* Now it is safe to enter macrocell in suspend mode */
wCNTR |= CNTR_FSUSP;
_SetCNTR(wCNTR);
/* force low-power mode in the macrocell */
wCNTR = _GetCNTR();
wCNTR |= CNTR_LPMODE;
_SetCNTR(wCNTR);
/*prepare entry in low power mode (STOP mode)*/
/* Select the regulator state in STOP mode*/
savePWR_CR = PWR->CR;
tmpreg = PWR->CR;
/* Clear PDDS and LPDS bits */
tmpreg &= ((uint32_t)0xFFFFFFFC);
/* Set LPDS bit according to PWR_Regulator value */
tmpreg |= PWR_Regulator_LowPower;
/* Store the new value */
PWR->CR = tmpreg;
/* Set SLEEPDEEP bit of Cortex System Control Register */
#if defined (STM32F303xC) || defined (STM32F37X)
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
#else
SCB->SCR |= SCB_SCR_SLEEPDEEP;
#endif
/* enter system in STOP mode, only when wakeup flag in not set */
if ((_GetISTR() & ISTR_WKUP) == 0) {
__WFI();
/* Reset SLEEPDEEP bit of Cortex System Control Register */
#if defined (STM32F303xC) || defined (STM32F37X)
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
#else
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP);
#endif
} else {
/* Clear Wakeup flag */
_SetISTR(CLR_WKUP);
/* clear FSUSP to abort entry in suspend mode */
wCNTR = _GetCNTR();
wCNTR &= ~CNTR_FSUSP;
_SetCNTR(wCNTR);
/*restore sleep mode configuration */
/* restore Power regulator config in sleep mode*/
PWR->CR = savePWR_CR;
/* Reset SLEEPDEEP bit of Cortex System Control Register */
#if defined (STM32F303xC) || defined (STM32F37X)
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
#else
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP);
#endif
}
}
/*******************************************************************************
* Function Name : Resume_Init
* Description : Handles wake-up restoring normal operations
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
void Resume_Init(void)
{
uint16_t wCNTR;
/* ------------------ ONLY WITH BUS-POWERED DEVICES ---------------------- */
/* restart the clocks */
/* ... */
/* CNTR_LPMODE = 0 */
wCNTR = _GetCNTR();
wCNTR &= (~CNTR_LPMODE);
_SetCNTR(wCNTR);
/* restore full power */
/* ... on connected devices */
Leave_LowPowerMode();
/* reset FSUSP bit */
_SetCNTR(IMR_MSK);
/* reverse suspend preparation */
/* ... */
}
/*******************************************************************************
* Function Name : Resume
* Description : This is the state machine handling resume operations and
* timing sequence. The control is based on the Resume structure
* variables and on the ESOF interrupt calling this subroutine
* without changing machine state.
* Input : a state machine value (RESUME_STATE)
* RESUME_ESOF doesn't change ResumeS.eState allowing
* decrementing of the ESOF counter in different states.
* Output : None.
* Return : None.
*******************************************************************************/
void Resume(RESUME_STATE eResumeSetVal)
{
uint16_t wCNTR;
if (eResumeSetVal != RESUME_ESOF)
ResumeS.eState = eResumeSetVal;
switch (ResumeS.eState) {
case RESUME_EXTERNAL:
if (remotewakeupon == 0) {
Resume_Init();
ResumeS.eState = RESUME_OFF;
} else /* RESUME detected during the RemoteWAkeup signalling => keep RemoteWakeup handling*/
{
ResumeS.eState = RESUME_ON;
}
break;
case RESUME_INTERNAL:
Resume_Init();
ResumeS.eState = RESUME_START;
remotewakeupon = 1;
break;
case RESUME_LATER:
ResumeS.bESOFcnt = 2;
ResumeS.eState = RESUME_WAIT;
break;
case RESUME_WAIT:
ResumeS.bESOFcnt--;
if (ResumeS.bESOFcnt == 0)
ResumeS.eState = RESUME_START;
break;
case RESUME_START:
wCNTR = _GetCNTR();
wCNTR |= CNTR_RESUME;
_SetCNTR(wCNTR);
ResumeS.eState = RESUME_ON;
ResumeS.bESOFcnt = 10;
break;
case RESUME_ON:
ResumeS.bESOFcnt--;
if (ResumeS.bESOFcnt == 0) {
wCNTR = _GetCNTR();
wCNTR &= (~CNTR_RESUME);
_SetCNTR(wCNTR);
ResumeS.eState = RESUME_OFF;
remotewakeupon = 0;
}
break;
case RESUME_OFF:
case RESUME_ESOF:
default:
ResumeS.eState = RESUME_OFF;
break;
}
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file usb_pwr.c
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Connection/disconnection & power management
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "usb_lib.h"
#include "usb_conf.h"
#include "usb_pwr.h"
#include "hw_config.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
__IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */
__IO boolean fSuspendEnabled = TRUE; /* true when suspend is possible */ // HJI
__IO uint32_t EP[8];
struct {
__IO RESUME_STATE eState;
__IO uint8_t bESOFcnt;
} ResumeS;
__IO uint32_t remotewakeupon = 0;
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Extern function prototypes ------------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : PowerOn
* Description :
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
RESULT PowerOn(void)
{
uint16_t wRegVal;
/*** cable plugged-in ? ***/
USB_Cable_Config(ENABLE);
/*** CNTR_PWDN = 0 ***/
wRegVal = CNTR_FRES;
_SetCNTR(wRegVal);
/*** CNTR_FRES = 0 ***/
wInterrupt_Mask = 0;
_SetCNTR(wInterrupt_Mask);
/*** Clear pending interrupts ***/
_SetISTR(0);
/*** Set interrupt mask ***/
wInterrupt_Mask = CNTR_RESETM | CNTR_SUSPM | CNTR_WKUPM;
_SetCNTR(wInterrupt_Mask);
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : PowerOff
* Description : handles switch-off conditions
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
RESULT PowerOff()
{
/* disable all interrupts and force USB reset */
_SetCNTR(CNTR_FRES);
/* clear interrupt status register */
_SetISTR(0);
/* Disable the Pull-Up*/
USB_Cable_Config(DISABLE);
/* switch-off device */
_SetCNTR(CNTR_FRES + CNTR_PDWN);
/* sw variables reset */
/* ... */
return USB_SUCCESS;
}
/*******************************************************************************
* Function Name : Suspend
* Description : sets suspend mode operating conditions
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
void Suspend(void)
{
uint32_t i = 0;
uint16_t wCNTR;
uint32_t tmpreg = 0;
__IO uint32_t savePWR_CR = 0;
/* suspend preparation */
/* ... */
/*Store CNTR value */
wCNTR = _GetCNTR();
/* This a sequence to apply a force RESET to handle a robustness case */
/*Store endpoints registers status */
for (i = 0; i < 8; i++)
EP[i] = _GetENDPOINT(i);
/* unmask RESET flag */
wCNTR |= CNTR_RESETM;
_SetCNTR(wCNTR);
/*apply FRES */
wCNTR |= CNTR_FRES;
_SetCNTR(wCNTR);
/*clear FRES*/
wCNTR &= ~CNTR_FRES;
_SetCNTR(wCNTR);
/*poll for RESET flag in ISTR*/
while ((_GetISTR() & ISTR_RESET) == 0)
;
/* clear RESET flag in ISTR */
_SetISTR((uint16_t)CLR_RESET);
/*restore Enpoints*/
for (i = 0; i < 8; i++)
_SetENDPOINT(i, EP[i]);
/* Now it is safe to enter macrocell in suspend mode */
wCNTR |= CNTR_FSUSP;
_SetCNTR(wCNTR);
/* force low-power mode in the macrocell */
wCNTR = _GetCNTR();
wCNTR |= CNTR_LPMODE;
_SetCNTR(wCNTR);
/*prepare entry in low power mode (STOP mode)*/
/* Select the regulator state in STOP mode*/
savePWR_CR = PWR->CR;
tmpreg = PWR->CR;
/* Clear PDDS and LPDS bits */
tmpreg &= ((uint32_t)0xFFFFFFFC);
/* Set LPDS bit according to PWR_Regulator value */
tmpreg |= PWR_Regulator_LowPower;
/* Store the new value */
PWR->CR = tmpreg;
/* Set SLEEPDEEP bit of Cortex System Control Register */
#if defined (STM32F303xC) || defined (STM32F37X)
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
#else
SCB->SCR |= SCB_SCR_SLEEPDEEP;
#endif
/* enter system in STOP mode, only when wakeup flag in not set */
if ((_GetISTR() & ISTR_WKUP) == 0) {
__WFI();
/* Reset SLEEPDEEP bit of Cortex System Control Register */
#if defined (STM32F303xC) || defined (STM32F37X)
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
#else
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP);
#endif
} else {
/* Clear Wakeup flag */
_SetISTR(CLR_WKUP);
/* clear FSUSP to abort entry in suspend mode */
wCNTR = _GetCNTR();
wCNTR &= ~CNTR_FSUSP;
_SetCNTR(wCNTR);
/*restore sleep mode configuration */
/* restore Power regulator config in sleep mode*/
PWR->CR = savePWR_CR;
/* Reset SLEEPDEEP bit of Cortex System Control Register */
#if defined (STM32F303xC) || defined (STM32F37X)
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
#else
SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP);
#endif
}
}
/*******************************************************************************
* Function Name : Resume_Init
* Description : Handles wake-up restoring normal operations
* Input : None.
* Output : None.
* Return : USB_SUCCESS.
*******************************************************************************/
void Resume_Init(void)
{
uint16_t wCNTR;
/* ------------------ ONLY WITH BUS-POWERED DEVICES ---------------------- */
/* restart the clocks */
/* ... */
/* CNTR_LPMODE = 0 */
wCNTR = _GetCNTR();
wCNTR &= (~CNTR_LPMODE);
_SetCNTR(wCNTR);
/* restore full power */
/* ... on connected devices */
Leave_LowPowerMode();
/* reset FSUSP bit */
_SetCNTR(IMR_MSK);
/* reverse suspend preparation */
/* ... */
}
/*******************************************************************************
* Function Name : Resume
* Description : This is the state machine handling resume operations and
* timing sequence. The control is based on the Resume structure
* variables and on the ESOF interrupt calling this subroutine
* without changing machine state.
* Input : a state machine value (RESUME_STATE)
* RESUME_ESOF doesn't change ResumeS.eState allowing
* decrementing of the ESOF counter in different states.
* Output : None.
* Return : None.
*******************************************************************************/
void Resume(RESUME_STATE eResumeSetVal)
{
uint16_t wCNTR;
if (eResumeSetVal != RESUME_ESOF)
ResumeS.eState = eResumeSetVal;
switch (ResumeS.eState) {
case RESUME_EXTERNAL:
if (remotewakeupon == 0) {
Resume_Init();
ResumeS.eState = RESUME_OFF;
} else /* RESUME detected during the RemoteWAkeup signalling => keep RemoteWakeup handling*/
{
ResumeS.eState = RESUME_ON;
}
break;
case RESUME_INTERNAL:
Resume_Init();
ResumeS.eState = RESUME_START;
remotewakeupon = 1;
break;
case RESUME_LATER:
ResumeS.bESOFcnt = 2;
ResumeS.eState = RESUME_WAIT;
break;
case RESUME_WAIT:
ResumeS.bESOFcnt--;
if (ResumeS.bESOFcnt == 0)
ResumeS.eState = RESUME_START;
break;
case RESUME_START:
wCNTR = _GetCNTR();
wCNTR |= CNTR_RESUME;
_SetCNTR(wCNTR);
ResumeS.eState = RESUME_ON;
ResumeS.bESOFcnt = 10;
break;
case RESUME_ON:
ResumeS.bESOFcnt--;
if (ResumeS.bESOFcnt == 0) {
wCNTR = _GetCNTR();
wCNTR &= (~CNTR_RESUME);
_SetCNTR(wCNTR);
ResumeS.eState = RESUME_OFF;
remotewakeupon = 0;
}
break;
case RESUME_OFF:
case RESUME_ESOF:
default:
ResumeS.eState = RESUME_OFF;
break;
}
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,68 +1,68 @@
/**
******************************************************************************
* @file usb_pwr.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Connection/disconnection & power management header
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_PWR_H
#define __USB_PWR_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef enum _RESUME_STATE {
RESUME_EXTERNAL,
RESUME_INTERNAL,
RESUME_LATER,
RESUME_WAIT,
RESUME_START,
RESUME_ON,
RESUME_OFF,
RESUME_ESOF
} RESUME_STATE;
typedef enum _DEVICE_STATE {
UNCONNECTED,
ATTACHED,
POWERED,
SUSPENDED,
ADDRESSED,
CONFIGURED
} DEVICE_STATE;
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void Suspend(void);
void Resume_Init(void);
void Resume(RESUME_STATE eResumeSetVal);
RESULT PowerOn(void);
RESULT PowerOff(void);
/* External variables --------------------------------------------------------*/
extern __IO uint32_t bDeviceState; /* USB device status */
extern __IO boolean fSuspendEnabled; /* true when suspend is possible */ // HJI
#endif /*__USB_PWR_H*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file usb_pwr.h
* @author MCD Application Team
* @version V4.0.0
* @date 21-January-2013
* @brief Connection/disconnection & power management header
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (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.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USB_PWR_H
#define __USB_PWR_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef enum _RESUME_STATE {
RESUME_EXTERNAL,
RESUME_INTERNAL,
RESUME_LATER,
RESUME_WAIT,
RESUME_START,
RESUME_ON,
RESUME_OFF,
RESUME_ESOF
} RESUME_STATE;
typedef enum _DEVICE_STATE {
UNCONNECTED,
ATTACHED,
POWERED,
SUSPENDED,
ADDRESSED,
CONFIGURED
} DEVICE_STATE;
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void Suspend(void);
void Resume_Init(void);
void Resume(RESUME_STATE eResumeSetVal);
RESULT PowerOn(void);
RESULT PowerOff(void);
/* External variables --------------------------------------------------------*/
extern __IO uint32_t bDeviceState; /* USB device status */
extern __IO boolean fSuspendEnabled; /* true when suspend is possible */ // HJI
#endif /*__USB_PWR_H*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -1,139 +1,139 @@
# A sample Makefile for building Google Test and using it in user
# tests. Please tweak it to suit your environment and project. You
# may want to move it to your project's root directory.
#
# SYNOPSIS:
#
# make [all] - makes everything.
# make TARGET - makes the given target.
# make clean - removes all files generated by make.
# Please tweak the following variable definitions as needed by your
# project, except GTEST_HEADERS, which you can use in your own targets
# but shouldn't modify.
# Points to the root of Google Test, relative to where this file is.
# Remember to tweak this if you move this file.
GTEST_DIR = ../../lib/test/gtest
# Where to find user code.
USER_DIR = ../main
TEST_DIR = unit
USER_INCLUDE_DIR = $(USER_DIR)
OBJECT_DIR = ../../obj/test
# Flags passed to the preprocessor.
# Set Google Test's header directory as a system directory, such that
# the compiler doesn't generate warnings in Google Test headers.
CPPFLAGS += -isystem $(GTEST_DIR)/inc
# Flags passed to the C++ compiler.
CXXFLAGS += -g -Wall -Wextra -pthread -ggdb -O0
# All tests produced by this Makefile. Remember to add new tests you
# created to the list.
TESTS = battery_unittest flight_imu_unittest gps_conversion_unittest telemetry_hott_unittest
# All Google Test headers. Usually you shouldn't change this
# definition.
GTEST_HEADERS = $(GTEST_DIR)/inc/gtest/*.h
# House-keeping build targets.
all : $(TESTS)
clean :
rm -rf $(TESTS) $(OBJECT_DIR)
# Builds gtest.a and gtest_main.a.
# Usually you shouldn't tweak such internal variables, indicated by a
# trailing _.
GTEST_SRCS_ = $(GTEST_DIR)/src/*.cc $(GTEST_DIR)/inc/gtest/*.h $(GTEST_HEADERS)
# For simplicity and to avoid depending on Google Test's
# implementation details, the dependencies specified below are
# conservative and not optimized. This is fine as Google Test
# compiles fast and for ordinary users its source rarely changes.
$(OBJECT_DIR)/gtest-all.o : $(GTEST_SRCS_)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) -I$(GTEST_DIR) $(CXXFLAGS) -c \
$(GTEST_DIR)/src/gtest-all.cc -o $@
$(OBJECT_DIR)/gtest_main.o : $(GTEST_SRCS_)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) -I$(GTEST_DIR) $(CXXFLAGS) -c \
$(GTEST_DIR)/src/gtest_main.cc -o $@
$(OBJECT_DIR)/gtest.a : $(OBJECT_DIR)/gtest-all.o
$(AR) $(ARFLAGS) $@ $^
$(OBJECT_DIR)/gtest_main.a : $(OBJECT_DIR)/gtest-all.o $(OBJECT_DIR)/gtest_main.o
$(AR) $(ARFLAGS) $@ $^
# Builds a sample test. A test should link with either gtest.a or
# gtest_main.a, depending on whether it defines its own main()
# function.
# includes in test dir must override includes in user dir
TEST_INCLUDE_DIRS := $(TEST_DIR) \
$(USER_INCLUDE_DIR)
TEST_CFLAGS = $(addprefix -I,$(TEST_INCLUDE_DIRS))
$(OBJECT_DIR)/sensors/battery.o : $(USER_DIR)/sensors/battery.c $(USER_DIR)/sensors/battery.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/sensors/battery.c -o $@
$(OBJECT_DIR)/battery_unittest.o : $(TEST_DIR)/battery_unittest.cc \
$(USER_DIR)/sensors/battery.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/battery_unittest.cc -o $@
battery_unittest : $(OBJECT_DIR)/sensors/battery.o $(OBJECT_DIR)/battery_unittest.o $(OBJECT_DIR)/gtest_main.a
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
$(OBJECT_DIR)/flight/imu.o : $(USER_DIR)/flight/imu.c $(USER_DIR)/flight/imu.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/imu.c -o $@
$(OBJECT_DIR)/flight_imu_unittest.o : $(TEST_DIR)/flight_imu_unittest.cc \
$(USER_DIR)/flight/imu.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/flight_imu_unittest.cc -o $@
flight_imu_unittest : $(OBJECT_DIR)/flight/imu.o $(OBJECT_DIR)/flight_imu_unittest.o $(OBJECT_DIR)/gtest_main.a
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
$(OBJECT_DIR)/io/gps_conversion.o : $(USER_DIR)/io/gps_conversion.c $(USER_DIR)/io/gps_conversion.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/gps_conversion.c -o $@
$(OBJECT_DIR)/gps_conversion_unittest.o : $(TEST_DIR)/gps_conversion_unittest.cc \
$(USER_DIR)/io/gps_conversion.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/gps_conversion_unittest.cc -o $@
gps_conversion_unittest : $(OBJECT_DIR)/io/gps_conversion.o $(OBJECT_DIR)/gps_conversion_unittest.o $(OBJECT_DIR)/gtest_main.a
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
$(OBJECT_DIR)/telemetry/hott.o : $(USER_DIR)/telemetry/hott.c $(USER_DIR)/telemetry/hott.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/telemetry/hott.c -o $@
$(OBJECT_DIR)/telemetry_hott_unittest.o : $(TEST_DIR)/telemetry_hott_unittest.cc \
$(USER_DIR)/telemetry/hott.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/telemetry_hott_unittest.cc -o $@
telemetry_hott_unittest :$(OBJECT_DIR)/telemetry/hott.o $(OBJECT_DIR)/telemetry_hott_unittest.o $(OBJECT_DIR)/io/gps_conversion.o $(OBJECT_DIR)/gtest_main.a
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
# A sample Makefile for building Google Test and using it in user
# tests. Please tweak it to suit your environment and project. You
# may want to move it to your project's root directory.
#
# SYNOPSIS:
#
# make [all] - makes everything.
# make TARGET - makes the given target.
# make clean - removes all files generated by make.
# Please tweak the following variable definitions as needed by your
# project, except GTEST_HEADERS, which you can use in your own targets
# but shouldn't modify.
# Points to the root of Google Test, relative to where this file is.
# Remember to tweak this if you move this file.
GTEST_DIR = ../../lib/test/gtest
# Where to find user code.
USER_DIR = ../main
TEST_DIR = unit
USER_INCLUDE_DIR = $(USER_DIR)
OBJECT_DIR = ../../obj/test
# Flags passed to the preprocessor.
# Set Google Test's header directory as a system directory, such that
# the compiler doesn't generate warnings in Google Test headers.
CPPFLAGS += -isystem $(GTEST_DIR)/inc
# Flags passed to the C++ compiler.
CXXFLAGS += -g -Wall -Wextra -pthread -ggdb -O0
# All tests produced by this Makefile. Remember to add new tests you
# created to the list.
TESTS = battery_unittest flight_imu_unittest gps_conversion_unittest telemetry_hott_unittest
# All Google Test headers. Usually you shouldn't change this
# definition.
GTEST_HEADERS = $(GTEST_DIR)/inc/gtest/*.h
# House-keeping build targets.
all : $(TESTS)
clean :
rm -rf $(TESTS) $(OBJECT_DIR)
# Builds gtest.a and gtest_main.a.
# Usually you shouldn't tweak such internal variables, indicated by a
# trailing _.
GTEST_SRCS_ = $(GTEST_DIR)/src/*.cc $(GTEST_DIR)/inc/gtest/*.h $(GTEST_HEADERS)
# For simplicity and to avoid depending on Google Test's
# implementation details, the dependencies specified below are
# conservative and not optimized. This is fine as Google Test
# compiles fast and for ordinary users its source rarely changes.
$(OBJECT_DIR)/gtest-all.o : $(GTEST_SRCS_)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) -I$(GTEST_DIR) $(CXXFLAGS) -c \
$(GTEST_DIR)/src/gtest-all.cc -o $@
$(OBJECT_DIR)/gtest_main.o : $(GTEST_SRCS_)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) -I$(GTEST_DIR) $(CXXFLAGS) -c \
$(GTEST_DIR)/src/gtest_main.cc -o $@
$(OBJECT_DIR)/gtest.a : $(OBJECT_DIR)/gtest-all.o
$(AR) $(ARFLAGS) $@ $^
$(OBJECT_DIR)/gtest_main.a : $(OBJECT_DIR)/gtest-all.o $(OBJECT_DIR)/gtest_main.o
$(AR) $(ARFLAGS) $@ $^
# Builds a sample test. A test should link with either gtest.a or
# gtest_main.a, depending on whether it defines its own main()
# function.
# includes in test dir must override includes in user dir
TEST_INCLUDE_DIRS := $(TEST_DIR) \
$(USER_INCLUDE_DIR)
TEST_CFLAGS = $(addprefix -I,$(TEST_INCLUDE_DIRS))
$(OBJECT_DIR)/sensors/battery.o : $(USER_DIR)/sensors/battery.c $(USER_DIR)/sensors/battery.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/sensors/battery.c -o $@
$(OBJECT_DIR)/battery_unittest.o : $(TEST_DIR)/battery_unittest.cc \
$(USER_DIR)/sensors/battery.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/battery_unittest.cc -o $@
battery_unittest : $(OBJECT_DIR)/sensors/battery.o $(OBJECT_DIR)/battery_unittest.o $(OBJECT_DIR)/gtest_main.a
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
$(OBJECT_DIR)/flight/imu.o : $(USER_DIR)/flight/imu.c $(USER_DIR)/flight/imu.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/imu.c -o $@
$(OBJECT_DIR)/flight_imu_unittest.o : $(TEST_DIR)/flight_imu_unittest.cc \
$(USER_DIR)/flight/imu.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/flight_imu_unittest.cc -o $@
flight_imu_unittest : $(OBJECT_DIR)/flight/imu.o $(OBJECT_DIR)/flight_imu_unittest.o $(OBJECT_DIR)/gtest_main.a
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
$(OBJECT_DIR)/io/gps_conversion.o : $(USER_DIR)/io/gps_conversion.c $(USER_DIR)/io/gps_conversion.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/gps_conversion.c -o $@
$(OBJECT_DIR)/gps_conversion_unittest.o : $(TEST_DIR)/gps_conversion_unittest.cc \
$(USER_DIR)/io/gps_conversion.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/gps_conversion_unittest.cc -o $@
gps_conversion_unittest : $(OBJECT_DIR)/io/gps_conversion.o $(OBJECT_DIR)/gps_conversion_unittest.o $(OBJECT_DIR)/gtest_main.a
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
$(OBJECT_DIR)/telemetry/hott.o : $(USER_DIR)/telemetry/hott.c $(USER_DIR)/telemetry/hott.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/telemetry/hott.c -o $@
$(OBJECT_DIR)/telemetry_hott_unittest.o : $(TEST_DIR)/telemetry_hott_unittest.cc \
$(USER_DIR)/telemetry/hott.h $(GTEST_HEADERS)
@mkdir -p $(dir $@)
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/telemetry_hott_unittest.cc -o $@
telemetry_hott_unittest :$(OBJECT_DIR)/telemetry/hott.o $(OBJECT_DIR)/telemetry_hott_unittest.o $(OBJECT_DIR)/io/gps_conversion.o $(OBJECT_DIR)/gtest_main.a
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@

View file

@ -1,75 +1,75 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <limits.h>
#include "sensors/battery.h"
#include "unittest_macros.h"
#include "gtest/gtest.h"
typedef struct batteryAdcToVoltageExpectation_s {
uint16_t adcReading;
uint16_t expectedVoltageInDeciVoltSteps;
} batteryAdcToVoltageExpectation_t;
#define ELEVEN_TO_ONE_VOLTAGE_DIVIDER 110 // (10k:1k) * 10 for 0.1V
TEST(BatteryTest, BatteryADCToVoltage)
{
// given
batteryConfig_t batteryConfig;
batteryConfig.vbatscale = ELEVEN_TO_ONE_VOLTAGE_DIVIDER;
batteryInit(&batteryConfig);
batteryAdcToVoltageExpectation_t batteryAdcToVoltageExpectations[] = {
{1420, 125},
{1430, 126},
{1440, 127},
{1890, 167},
{1900, 168},
{1910, 169}
};
uint8_t testIterationCount = sizeof(batteryAdcToVoltageExpectations) / sizeof(batteryAdcToVoltageExpectation_t);
// expect
for (uint8_t index = 0; index < testIterationCount; index ++) {
batteryAdcToVoltageExpectation_t *batteryAdcToVoltageExpectation = &batteryAdcToVoltageExpectations[index];
printf("adcReading: %d\n", batteryAdcToVoltageExpectation->adcReading);
uint16_t pointOneVoltSteps = batteryAdcToVoltage(batteryAdcToVoltageExpectation->adcReading);
EXPECT_EQ(pointOneVoltSteps, batteryAdcToVoltageExpectation->expectedVoltageInDeciVoltSteps);
}
}
// STUBS
uint16_t adcGetChannel(uint8_t channel)
{
UNUSED(channel);
return 0;
}
void delay(uint32_t ms)
{
UNUSED(ms);
return;
}
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <limits.h>
#include "sensors/battery.h"
#include "unittest_macros.h"
#include "gtest/gtest.h"
typedef struct batteryAdcToVoltageExpectation_s {
uint16_t adcReading;
uint16_t expectedVoltageInDeciVoltSteps;
} batteryAdcToVoltageExpectation_t;
#define ELEVEN_TO_ONE_VOLTAGE_DIVIDER 110 // (10k:1k) * 10 for 0.1V
TEST(BatteryTest, BatteryADCToVoltage)
{
// given
batteryConfig_t batteryConfig;
batteryConfig.vbatscale = ELEVEN_TO_ONE_VOLTAGE_DIVIDER;
batteryInit(&batteryConfig);
batteryAdcToVoltageExpectation_t batteryAdcToVoltageExpectations[] = {
{1420, 125},
{1430, 126},
{1440, 127},
{1890, 167},
{1900, 168},
{1910, 169}
};
uint8_t testIterationCount = sizeof(batteryAdcToVoltageExpectations) / sizeof(batteryAdcToVoltageExpectation_t);
// expect
for (uint8_t index = 0; index < testIterationCount; index ++) {
batteryAdcToVoltageExpectation_t *batteryAdcToVoltageExpectation = &batteryAdcToVoltageExpectations[index];
printf("adcReading: %d\n", batteryAdcToVoltageExpectation->adcReading);
uint16_t pointOneVoltSteps = batteryAdcToVoltage(batteryAdcToVoltageExpectation->adcReading);
EXPECT_EQ(pointOneVoltSteps, batteryAdcToVoltageExpectation->expectedVoltageInDeciVoltSteps);
}
}
// STUBS
uint16_t adcGetChannel(uint8_t channel)
{
UNUSED(channel);
return 0;
}
void delay(uint32_t ms)
{
UNUSED(ms);
return;
}

View file

@ -1,115 +1,115 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdbool.h>
#include <limits.h>
#define BARO
#include "common/axis.h"
#include "flight/flight.h"
#include "sensors/sensors.h"
#include "drivers/accgyro.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "config/runtime_config.h"
#include "flight/mixer.h"
#include "flight/imu.h"
#include "unittest_macros.h"
#include "gtest/gtest.h"
#define DOWNWARDS_THRUST true
#define UPWARDS_THRUST false
bool isThrustFacingDownwards(rollAndPitchInclination_t *inclinations);
typedef struct inclinationExpectation_s {
rollAndPitchInclination_t inclination;
bool expectDownwardsThrust;
} inclinationExpectation_t;
TEST(FlightImuTest, IsThrustFacingDownwards)
{
// given
inclinationExpectation_t inclinationExpectations[] = {
{ { 0, 0 }, DOWNWARDS_THRUST },
{ { 799, 799 }, DOWNWARDS_THRUST },
{ { 800, 799 }, UPWARDS_THRUST },
{ { 799, 800 }, UPWARDS_THRUST },
{ { 800, 800 }, UPWARDS_THRUST },
{ { 801, 801 }, UPWARDS_THRUST },
{ { -799, -799 }, DOWNWARDS_THRUST },
{ { -800, -799 }, UPWARDS_THRUST },
{ { -799, -800 }, UPWARDS_THRUST },
{ { -800, -800 }, UPWARDS_THRUST },
{ { -801, -801 }, UPWARDS_THRUST }
};
uint8_t testIterationCount = sizeof(inclinationExpectations) / sizeof(inclinationExpectation_t);
// expect
for (uint8_t index = 0; index < testIterationCount; index ++) {
inclinationExpectation_t *angleInclinationExpectation = &inclinationExpectations[index];
printf("iteration: %d\n", index);
bool result = isThrustFacingDownwards(&angleInclinationExpectation->inclination);
EXPECT_EQ(angleInclinationExpectation->expectDownwardsThrust, result);
}
}
// STUBS
uint16_t acc_1G;
int16_t heading;
flags_t f;
gyro_t gyro;
int16_t magADC[XYZ_AXIS_COUNT];
int32_t BaroAlt;
int16_t debug[4];
void gyroGetADC(void) {};
bool sensors(uint32_t mask)
{
UNUSED(mask);
return false;
};
void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
{
UNUSED(rollAndPitchTrims);
}
uint32_t micros(void) { return 0; }
bool isBaroCalibrationComplete(void) { return true; }
void performBaroCalibrationCycle(void) {}
int32_t baroCalculateAltitude(void) { return 0; }
int constrain(int amt, int low, int high)
{
UNUSED(amt);
UNUSED(low);
UNUSED(high);
return 0;
}
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdbool.h>
#include <limits.h>
#define BARO
#include "common/axis.h"
#include "flight/flight.h"
#include "sensors/sensors.h"
#include "drivers/accgyro.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "config/runtime_config.h"
#include "flight/mixer.h"
#include "flight/imu.h"
#include "unittest_macros.h"
#include "gtest/gtest.h"
#define DOWNWARDS_THRUST true
#define UPWARDS_THRUST false
bool isThrustFacingDownwards(rollAndPitchInclination_t *inclinations);
typedef struct inclinationExpectation_s {
rollAndPitchInclination_t inclination;
bool expectDownwardsThrust;
} inclinationExpectation_t;
TEST(FlightImuTest, IsThrustFacingDownwards)
{
// given
inclinationExpectation_t inclinationExpectations[] = {
{ { 0, 0 }, DOWNWARDS_THRUST },
{ { 799, 799 }, DOWNWARDS_THRUST },
{ { 800, 799 }, UPWARDS_THRUST },
{ { 799, 800 }, UPWARDS_THRUST },
{ { 800, 800 }, UPWARDS_THRUST },
{ { 801, 801 }, UPWARDS_THRUST },
{ { -799, -799 }, DOWNWARDS_THRUST },
{ { -800, -799 }, UPWARDS_THRUST },
{ { -799, -800 }, UPWARDS_THRUST },
{ { -800, -800 }, UPWARDS_THRUST },
{ { -801, -801 }, UPWARDS_THRUST }
};
uint8_t testIterationCount = sizeof(inclinationExpectations) / sizeof(inclinationExpectation_t);
// expect
for (uint8_t index = 0; index < testIterationCount; index ++) {
inclinationExpectation_t *angleInclinationExpectation = &inclinationExpectations[index];
printf("iteration: %d\n", index);
bool result = isThrustFacingDownwards(&angleInclinationExpectation->inclination);
EXPECT_EQ(angleInclinationExpectation->expectDownwardsThrust, result);
}
}
// STUBS
uint16_t acc_1G;
int16_t heading;
flags_t f;
gyro_t gyro;
int16_t magADC[XYZ_AXIS_COUNT];
int32_t BaroAlt;
int16_t debug[4];
void gyroGetADC(void) {};
bool sensors(uint32_t mask)
{
UNUSED(mask);
return false;
};
void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
{
UNUSED(rollAndPitchTrims);
}
uint32_t micros(void) { return 0; }
bool isBaroCalibrationComplete(void) { return true; }
void performBaroCalibrationCycle(void) {}
int32_t baroCalculateAltitude(void) { return 0; }
int constrain(int amt, int low, int high)
{
UNUSED(amt);
UNUSED(low);
UNUSED(high);
return 0;
}

View file

@ -1,69 +1,69 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <limits.h>
#include "io/gps_conversion.h"
#include "unittest_macros.h"
#include "gtest/gtest.h"
// See http://en.wikipedia.org/wiki/Geographic_coordinate_conversion
TEST(GpsConversionTest, GPSCoordToDegrees_BadString)
{
// expect
uint32_t result = GPS_coord_to_degrees("diediedie");
EXPECT_EQ(result, 0);
}
typedef struct gpsConversionExpectation_s {
char *coord;
uint32_t degrees;
} gpsConversionExpectation_t;
TEST(GpsConversionTest, GPSCoordToDegrees_NMEA_Values)
{
gpsConversionExpectation_t gpsConversionExpectations[] = {
{"0.0", 0},
{"000.0", 0},
{"00000.0000", 0},
{"0.0001", 16}, // smallest value
{"25599.9999", 2566666650UL}, // largest value
{"25599.99999", 2566666650UL}, // too many fractional digits
{"25699.9999", 16666650UL}, // overflowed without detection
{"5128.3727", 514728783UL},
{"5321.6802", 533613366UL},
{"00630.3372", 65056200UL},
};
// expect
uint8_t testIterationCount = sizeof(gpsConversionExpectations) / sizeof(gpsConversionExpectation_t);
// expect
for (uint8_t index = 0; index < testIterationCount; index ++) {
gpsConversionExpectation_t *expectation = &gpsConversionExpectations[index];
printf("iteration: %d\n", index);
uint32_t result = GPS_coord_to_degrees(expectation->coord);
EXPECT_EQ(result, expectation->degrees);
}
}
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <limits.h>
#include "io/gps_conversion.h"
#include "unittest_macros.h"
#include "gtest/gtest.h"
// See http://en.wikipedia.org/wiki/Geographic_coordinate_conversion
TEST(GpsConversionTest, GPSCoordToDegrees_BadString)
{
// expect
uint32_t result = GPS_coord_to_degrees("diediedie");
EXPECT_EQ(result, 0);
}
typedef struct gpsConversionExpectation_s {
char *coord;
uint32_t degrees;
} gpsConversionExpectation_t;
TEST(GpsConversionTest, GPSCoordToDegrees_NMEA_Values)
{
gpsConversionExpectation_t gpsConversionExpectations[] = {
{"0.0", 0},
{"000.0", 0},
{"00000.0000", 0},
{"0.0001", 16}, // smallest value
{"25599.9999", 2566666650UL}, // largest value
{"25599.99999", 2566666650UL}, // too many fractional digits
{"25699.9999", 16666650UL}, // overflowed without detection
{"5128.3727", 514728783UL},
{"5321.6802", 533613366UL},
{"00630.3372", 65056200UL},
};
// expect
uint8_t testIterationCount = sizeof(gpsConversionExpectations) / sizeof(gpsConversionExpectation_t);
// expect
for (uint8_t index = 0; index < testIterationCount; index ++) {
gpsConversionExpectation_t *expectation = &gpsConversionExpectations[index];
printf("iteration: %d\n", index);
uint32_t result = GPS_coord_to_degrees(expectation->coord);
EXPECT_EQ(result, expectation->degrees);
}
}

View file

@ -1,220 +1,220 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <limits.h>
#include "platform.h"
#include "common/axis.h"
#include "drivers/system.h"
#include "drivers/serial.h"
#include "io/serial.h"
#include "config/runtime_config.h"
#include "sensors/sensors.h"
#include "flight/flight.h"
#include "io/gps.h"
#include "sensors/battery.h"
#include "telemetry/telemetry.h"
#include "telemetry/hott.h"
#include "io/gps_conversion.h"
#include "unittest_macros.h"
#include "gtest/gtest.h"
void addGPSCoordinates(HOTT_GPS_MSG_t *hottGPSMessage, int32_t latitude, int32_t longitude);
// See http://en.wikipedia.org/wiki/Geographic_coordinate_conversion
HOTT_GPS_MSG_t hottGPSMessage;
HOTT_GPS_MSG_t *getGPSMessageForTest(void)
{
memset(&hottGPSMessage, 0, sizeof(hottGPSMessage));
return &hottGPSMessage;
}
TEST(TelemetryHottTest, UpdateGPSCoordinates1)
{
// given
HOTT_GPS_MSG_t *hottGPSMessage = getGPSMessageForTest();
// Mayrhofen, Austria
uint32_t longitude = GPS_coord_to_degrees("4710.5186");
uint32_t latitude = GPS_coord_to_degrees("1151.4252");
// when
addGPSCoordinates(hottGPSMessage, latitude, longitude);
// then
EXPECT_EQ(hottGPSMessage->pos_NS, 0);
EXPECT_EQ(hottGPSMessage->pos_NS_dm_H << 8 | hottGPSMessage->pos_NS_dm_L, 1151);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_NS_sec_H << 8 | hottGPSMessage->pos_NS_sec_L), 4251);
EXPECT_EQ(hottGPSMessage->pos_EW, 0);
EXPECT_EQ(hottGPSMessage->pos_EW_dm_H << 8 | hottGPSMessage->pos_EW_dm_L, 4710);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_EW_sec_H << 8 | hottGPSMessage->pos_EW_sec_L), 5186);
}
TEST(TelemetryHottTest, UpdateGPSCoordinates2)
{
// given
HOTT_GPS_MSG_t *hottGPSMessage = getGPSMessageForTest();
// Hampstead Heath, London
// 51.563886, -0.159960
int32_t longitude = GPS_coord_to_degrees("5156.3886");
int32_t latitude = -GPS_coord_to_degrees("015.9960");
// when
addGPSCoordinates(hottGPSMessage, longitude, latitude);
// then
EXPECT_EQ(hottGPSMessage->pos_NS, 0);
EXPECT_EQ(hottGPSMessage->pos_NS_dm_H << 8 | hottGPSMessage->pos_NS_dm_L, 5156);
EXPECT_EQ(hottGPSMessage->pos_NS_sec_H << 8 | hottGPSMessage->pos_NS_sec_L, 3886);
EXPECT_EQ(hottGPSMessage->pos_EW, 1);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_EW_dm_H << 8 | hottGPSMessage->pos_EW_dm_L), -15);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_EW_sec_H << 8 | hottGPSMessage->pos_EW_sec_L), -9960);
}
TEST(TelemetryHottTest, UpdateGPSCoordinates3)
{
// given
HOTT_GPS_MSG_t *hottGPSMessage = getGPSMessageForTest();
int32_t longitude = -GPS_coord_to_degrees("17999.9999");
int32_t latitude = GPS_coord_to_degrees("8999.9999");
// when
addGPSCoordinates(hottGPSMessage, longitude, latitude);
// then
EXPECT_EQ(hottGPSMessage->pos_NS, 1);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_NS_dm_H << 8 | hottGPSMessage->pos_NS_dm_L), -18039);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_NS_sec_H << 8 | hottGPSMessage->pos_NS_sec_L), -9999);
EXPECT_EQ(hottGPSMessage->pos_EW, 0);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_EW_dm_H << 8 | hottGPSMessage->pos_EW_dm_L), 9039);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_EW_sec_H << 8 | hottGPSMessage->pos_EW_sec_L), 9999);
}
TEST(TelemetryHottTest, PrepareGPSMessage_Altitude1m)
{
// given
HOTT_GPS_MSG_t *hottGPSMessage = getGPSMessageForTest();
f.GPS_FIX = 1;
uint16_t altitudeInMeters = 1;
GPS_altitude = altitudeInMeters * (1 / 0.1f); // 1 = 0.1m
// when
hottPrepareGPSResponse(hottGPSMessage);
// then
EXPECT_EQ((int16_t)(hottGPSMessage->altitude_H << 8 | hottGPSMessage->altitude_L), 1 + HOTT_GPS_ALTITUDE_OFFSET);
}
// STUBS
int16_t debug[4];
uint8_t GPS_numSat;
flags_t f;
int32_t GPS_coord[2];
uint16_t GPS_speed; // speed in 0.1m/s
uint16_t GPS_distanceToHome; // distance to home point in meters
uint16_t GPS_altitude; // altitude in 0.1m
uint8_t vbat;
int16_t GPS_directionToHome; // direction to home or hol point in degrees
uint32_t micros(void) { return 0; }
uint8_t serialTotalBytesWaiting(serialPort_t *instance) {
UNUSED(instance);
return 0;
}
uint8_t serialRead(serialPort_t *instance) {
UNUSED(instance);
return 0;
}
void serialWrite(serialPort_t *instance, uint8_t ch) {
UNUSED(instance);
UNUSED(ch);
}
void serialSetMode(serialPort_t *instance, portMode_t mode) {
UNUSED(instance);
UNUSED(mode);
}
void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate) {
UNUSED(instance);
UNUSED(baudRate);
}
void beginSerialPortFunction(serialPort_t *port, serialPortFunction_e function) {
UNUSED(port);
UNUSED(function);
}
void endSerialPortFunction(serialPort_t *port, serialPortFunction_e function) {
UNUSED(port);
UNUSED(function);
}
serialPort_t *openSerialPort(serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion) {
UNUSED(functionMask);
UNUSED(baudRate);
UNUSED(callback);
UNUSED(mode);
UNUSED(inversion);
return NULL;
}
serialPort_t *findOpenSerialPort(uint16_t functionMask) {
UNUSED(functionMask);
return NULL;
}
bool sensors(uint32_t mask) {
UNUSED(mask);
return false;
}
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <limits.h>
#include "platform.h"
#include "common/axis.h"
#include "drivers/system.h"
#include "drivers/serial.h"
#include "io/serial.h"
#include "config/runtime_config.h"
#include "sensors/sensors.h"
#include "flight/flight.h"
#include "io/gps.h"
#include "sensors/battery.h"
#include "telemetry/telemetry.h"
#include "telemetry/hott.h"
#include "io/gps_conversion.h"
#include "unittest_macros.h"
#include "gtest/gtest.h"
void addGPSCoordinates(HOTT_GPS_MSG_t *hottGPSMessage, int32_t latitude, int32_t longitude);
// See http://en.wikipedia.org/wiki/Geographic_coordinate_conversion
HOTT_GPS_MSG_t hottGPSMessage;
HOTT_GPS_MSG_t *getGPSMessageForTest(void)
{
memset(&hottGPSMessage, 0, sizeof(hottGPSMessage));
return &hottGPSMessage;
}
TEST(TelemetryHottTest, UpdateGPSCoordinates1)
{
// given
HOTT_GPS_MSG_t *hottGPSMessage = getGPSMessageForTest();
// Mayrhofen, Austria
uint32_t longitude = GPS_coord_to_degrees("4710.5186");
uint32_t latitude = GPS_coord_to_degrees("1151.4252");
// when
addGPSCoordinates(hottGPSMessage, latitude, longitude);
// then
EXPECT_EQ(hottGPSMessage->pos_NS, 0);
EXPECT_EQ(hottGPSMessage->pos_NS_dm_H << 8 | hottGPSMessage->pos_NS_dm_L, 1151);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_NS_sec_H << 8 | hottGPSMessage->pos_NS_sec_L), 4251);
EXPECT_EQ(hottGPSMessage->pos_EW, 0);
EXPECT_EQ(hottGPSMessage->pos_EW_dm_H << 8 | hottGPSMessage->pos_EW_dm_L, 4710);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_EW_sec_H << 8 | hottGPSMessage->pos_EW_sec_L), 5186);
}
TEST(TelemetryHottTest, UpdateGPSCoordinates2)
{
// given
HOTT_GPS_MSG_t *hottGPSMessage = getGPSMessageForTest();
// Hampstead Heath, London
// 51.563886, -0.159960
int32_t longitude = GPS_coord_to_degrees("5156.3886");
int32_t latitude = -GPS_coord_to_degrees("015.9960");
// when
addGPSCoordinates(hottGPSMessage, longitude, latitude);
// then
EXPECT_EQ(hottGPSMessage->pos_NS, 0);
EXPECT_EQ(hottGPSMessage->pos_NS_dm_H << 8 | hottGPSMessage->pos_NS_dm_L, 5156);
EXPECT_EQ(hottGPSMessage->pos_NS_sec_H << 8 | hottGPSMessage->pos_NS_sec_L, 3886);
EXPECT_EQ(hottGPSMessage->pos_EW, 1);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_EW_dm_H << 8 | hottGPSMessage->pos_EW_dm_L), -15);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_EW_sec_H << 8 | hottGPSMessage->pos_EW_sec_L), -9960);
}
TEST(TelemetryHottTest, UpdateGPSCoordinates3)
{
// given
HOTT_GPS_MSG_t *hottGPSMessage = getGPSMessageForTest();
int32_t longitude = -GPS_coord_to_degrees("17999.9999");
int32_t latitude = GPS_coord_to_degrees("8999.9999");
// when
addGPSCoordinates(hottGPSMessage, longitude, latitude);
// then
EXPECT_EQ(hottGPSMessage->pos_NS, 1);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_NS_dm_H << 8 | hottGPSMessage->pos_NS_dm_L), -18039);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_NS_sec_H << 8 | hottGPSMessage->pos_NS_sec_L), -9999);
EXPECT_EQ(hottGPSMessage->pos_EW, 0);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_EW_dm_H << 8 | hottGPSMessage->pos_EW_dm_L), 9039);
EXPECT_EQ((int16_t)(hottGPSMessage->pos_EW_sec_H << 8 | hottGPSMessage->pos_EW_sec_L), 9999);
}
TEST(TelemetryHottTest, PrepareGPSMessage_Altitude1m)
{
// given
HOTT_GPS_MSG_t *hottGPSMessage = getGPSMessageForTest();
f.GPS_FIX = 1;
uint16_t altitudeInMeters = 1;
GPS_altitude = altitudeInMeters * (1 / 0.1f); // 1 = 0.1m
// when
hottPrepareGPSResponse(hottGPSMessage);
// then
EXPECT_EQ((int16_t)(hottGPSMessage->altitude_H << 8 | hottGPSMessage->altitude_L), 1 + HOTT_GPS_ALTITUDE_OFFSET);
}
// STUBS
int16_t debug[4];
uint8_t GPS_numSat;
flags_t f;
int32_t GPS_coord[2];
uint16_t GPS_speed; // speed in 0.1m/s
uint16_t GPS_distanceToHome; // distance to home point in meters
uint16_t GPS_altitude; // altitude in 0.1m
uint8_t vbat;
int16_t GPS_directionToHome; // direction to home or hol point in degrees
uint32_t micros(void) { return 0; }
uint8_t serialTotalBytesWaiting(serialPort_t *instance) {
UNUSED(instance);
return 0;
}
uint8_t serialRead(serialPort_t *instance) {
UNUSED(instance);
return 0;
}
void serialWrite(serialPort_t *instance, uint8_t ch) {
UNUSED(instance);
UNUSED(ch);
}
void serialSetMode(serialPort_t *instance, portMode_t mode) {
UNUSED(instance);
UNUSED(mode);
}
void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate) {
UNUSED(instance);
UNUSED(baudRate);
}
void beginSerialPortFunction(serialPort_t *port, serialPortFunction_e function) {
UNUSED(port);
UNUSED(function);
}
void endSerialPortFunction(serialPort_t *port, serialPortFunction_e function) {
UNUSED(port);
UNUSED(function);
}
serialPort_t *openSerialPort(serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion) {
UNUSED(functionMask);
UNUSED(baudRate);
UNUSED(callback);
UNUSED(mode);
UNUSED(inversion);
return NULL;
}
serialPort_t *findOpenSerialPort(uint16_t functionMask) {
UNUSED(functionMask);
return NULL;
}
bool sensors(uint32_t mask) {
UNUSED(mask);
return false;
}