├── .gitignore ├── ProjectTemplate.zip ├── README.md └── libraries ├── Application ├── AttitudeControl │ ├── AttitudeControl.cpp │ └── AttitudeControl.h ├── PositionLoop │ ├── PositionLoop.cpp │ └── PositionLoop.h ├── Servo │ ├── Servo.cpp │ └── Servo.h └── VelocityLoop │ ├── VelocityLoop.cpp │ └── VelocityLoop.h ├── OffChip ├── AHRS │ ├── AHRS.h │ ├── AHRS_DCM.cpp │ └── AHRS_DCM.h ├── BLDCMotor │ ├── BLDCMotor.cpp │ └── BLDCMotor.h ├── Barometer │ ├── Barometer.h │ ├── MS561101.cpp │ └── MS561101.h ├── Compass │ ├── Compass.h │ ├── HMC5883.cpp │ └── HMC5883.h ├── DHT12 │ ├── DHT12.cpp │ └── DHT12.h ├── ESCMotor │ ├── ESCMotor.cpp │ └── ESCMotor.h ├── GPRS │ ├── GPRS.cpp │ └── GPRS.h ├── GPS │ ├── GPS.cpp │ └── GPS.h ├── Gimbal │ ├── Gimbal.cpp │ └── Gimbal.h ├── HMI │ ├── HMI.cpp │ └── HMI.h ├── InertialSensor │ ├── InertialSensor.cpp │ ├── InertialSensor.h │ ├── MPU6050.cpp │ └── MPU6050.h ├── Joystick │ ├── Joystick.cpp │ └── Joystick.h ├── LED │ ├── LED.cpp │ └── LED.h ├── MFRC522 │ ├── MFRC522.cpp │ └── MFRC522.h ├── MHZ14 │ ├── MHZ14.cpp │ └── MHZ14.h ├── Monitor │ ├── Monitor.cpp │ └── Monitor.h ├── Motor │ ├── StepMotor.cpp │ └── StepMotor.h ├── NRF24L01 │ ├── Remade.md │ ├── demo │ │ ├── NRF24L01.uvprojx │ │ ├── RTE │ │ │ ├── Device │ │ │ │ └── STM32F103C8 │ │ │ │ │ ├── RTE_Device.h │ │ │ │ │ ├── startup_stm32f10x_md.s │ │ │ │ │ ├── stm32f10x_conf.h │ │ │ │ │ └── system_stm32f10x.c │ │ │ └── RTE_Components.h │ │ └── main.cpp │ ├── lib │ │ ├── NRF24L01.cpp │ │ └── NRF24L01.h │ └── 两机通讯(中断) │ │ ├── FourAxisByStm32(接收) │ │ ├── FourAxisByStm32.uvprojx │ │ ├── IMU │ │ │ ├── CRC.cpp │ │ │ ├── CRC.h │ │ │ ├── HMC5883L.cpp │ │ │ ├── HMC5883L.h │ │ │ ├── Matrix3.h │ │ │ ├── Quaternion.h │ │ │ ├── Vector3.h │ │ │ ├── attitude.cpp │ │ │ ├── attitude.h │ │ │ ├── mpu6050.cpp │ │ │ ├── mpu6050.h │ │ │ └── 新建文件夹 │ │ │ │ ├── mpu6050.cpp │ │ │ │ └── mpu6050.h │ │ ├── Lib │ │ │ ├── Communication.cpp │ │ │ ├── Communication.h │ │ │ ├── Control.cpp │ │ │ ├── Control.h │ │ │ ├── Delay.cpp │ │ │ ├── Delay.h │ │ │ ├── F103_PWM.cpp │ │ │ ├── F103_PWM.h │ │ │ ├── FIFOBuffer.h │ │ │ ├── Flash.cpp │ │ │ ├── Flash.h │ │ │ ├── GPIO.cpp │ │ │ ├── GPIO.h │ │ │ ├── I2C.cpp │ │ │ ├── I2C.h │ │ │ ├── Interrupt.cpp │ │ │ ├── Interrupt.h │ │ │ ├── LED.cpp │ │ │ ├── LED.h │ │ │ ├── NRF24L01.cpp │ │ │ ├── NRF24L01.h │ │ │ ├── SPI.cpp │ │ │ ├── SPI.h │ │ │ ├── Sensor.h │ │ │ ├── TaskManager.cpp │ │ │ ├── TaskManager.h │ │ │ ├── Timer.cpp │ │ │ ├── Timer.h │ │ │ ├── USART.cpp │ │ │ ├── USART.h │ │ │ ├── eeprom.cpp │ │ │ └── eeprom.h │ │ ├── RTE │ │ │ ├── Device │ │ │ │ └── STM32F103C8 │ │ │ │ │ ├── RTE_Device.h │ │ │ │ │ ├── startup_stm32f10x_md.s │ │ │ │ │ ├── stm32f10x_conf.h │ │ │ │ │ └── system_stm32f10x.c │ │ │ └── RTE_Components.h │ │ └── main.cpp │ │ └── test(发送) │ │ ├── demo │ │ ├── NRF24L01.uvprojx │ │ ├── RTE │ │ │ ├── Device │ │ │ │ └── STM32F103C8 │ │ │ │ │ ├── RTE_Device.h │ │ │ │ │ ├── startup_stm32f10x_md.s │ │ │ │ │ ├── stm32f10x_conf.h │ │ │ │ │ └── system_stm32f10x.c │ │ │ └── RTE_Components.h │ │ └── main.cpp │ │ └── lib │ │ ├── Delay.cpp │ │ ├── Delay.h │ │ ├── F103_PWM.cpp │ │ ├── F103_PWM.h │ │ ├── FIFOBuffer.h │ │ ├── GPIO.cpp │ │ ├── GPIO.h │ │ ├── HMC5883L.cpp │ │ ├── HMC5883L.h │ │ ├── I2C.cpp │ │ ├── I2C.h │ │ ├── Interrupt.cpp │ │ ├── Interrupt.h │ │ ├── LED.cpp │ │ ├── LED.h │ │ ├── NRF24L01.cpp │ │ ├── NRF24L01.h │ │ ├── SPI.cpp │ │ ├── SPI.h │ │ ├── TaskManager.cpp │ │ ├── TaskManager.h │ │ ├── USART.cpp │ │ ├── USART.h │ │ ├── Vector3.h │ │ ├── mpu6050.cpp │ │ └── mpu6050.h ├── Print │ ├── DPPrint.cpp │ └── DPPrint.h ├── RemoteControl │ ├── RemoteControl.cpp │ └── RemoteControl.h ├── Remoter │ ├── Remoter.h │ ├── Remoter_PWM_EXIT.cpp │ ├── Remoter_PWM_EXIT.h │ ├── Remoter_PWM_TIM.cpp │ └── Remoter_PWM_TIM.h ├── SHARP_1014_PM2_5 │ ├── SHARP_1014_PM2_5.cpp │ └── SHARP_1014_PM2_5.h ├── SHARP_1051_PM2_5 │ ├── SHARP_PM2_5.cpp │ └── SHARP_PM2_5.h ├── SHT2X │ ├── SHT2X.cpp │ └── SHT2X.h ├── Sensor.h ├── TVOC │ ├── TVOC.cpp │ └── TVOC.h ├── Ultrasonic │ ├── Ultrasonic.cpp │ └── Ultrasonic.h ├── W25QXX │ ├── W25QXX.cpp │ └── W25QXX.h ├── ZPH01 │ ├── Senser.h │ ├── ZPH01.cpp │ └── ZPH01.h ├── esp8266 │ ├── README.md │ ├── Socket_esp8266.cpp │ ├── Socket_esp8266.h │ ├── esp8266.cpp │ ├── esp8266.h │ └── socket.h └── yishan_PM2_5 │ ├── yishan_PM2_5.cpp │ └── yishan_PM2_5.h ├── OnChip ├── ADC │ ├── ADC.cpp │ └── ADC.h ├── GPIO │ ├── GPIO.cpp │ └── GPIO.h ├── IIC │ ├── I2C.cpp │ ├── I2C.h │ ├── I2CDevice.h │ ├── IIC.cpp │ └── IIC.h ├── InputCapture │ ├── InputCapture_EXIT.cpp │ ├── InputCapture_EXIT.h │ ├── InputCapture_TIM.cpp │ └── InputCapture_TIM.h ├── PWM │ ├── PWM.cpp │ └── PWM.h ├── SPI │ ├── SPI.cpp │ └── SPI.h ├── SerialPort │ ├── USART.cpp │ └── USART.h ├── SoftwareI2C │ ├── SoftwareI2C.cpp │ ├── SoftwareI2C.h │ └── sys │ │ ├── sys.c │ │ └── sys.h └── Timer │ ├── Timer.cpp │ └── Timer.h ├── System ├── Configuration.h ├── Interrupt │ ├── Interrupt.cpp │ └── Interrupt.h └── TaskManager │ ├── TaskManager.cpp │ └── TaskManager.h └── ToolBox ├── Buffer ├── DataFrame.h └── FIFOBuffer.h ├── Control └── PIDParameter.h ├── GidLink ├── GidLink.cpp └── GidLink.h └── Math ├── AHRS_Quater.cpp ├── AHRS_Quater.h ├── MathTool.h ├── Matrix3.h ├── Quaternion.cpp ├── Quaternion.h ├── Vector3.h └── Vector4.h /.gitignore: -------------------------------------------------------------------------------- 1 | # Compiled Object files 2 | *.slo 3 | *.lo 4 | *.o 5 | 6 | # Compiled Dynamic libraries 7 | *.so 8 | *.dylib 9 | 10 | # Compiled Static libraries 11 | *.lai 12 | *.la 13 | *.a 14 | 15 | #out folder 16 | out 17 | listing 18 | Objects 19 | listings 20 | Listings 21 | 22 | #MDK project file 23 | JLinkLog.txt 24 | JLinkSettings.ini 25 | *.guild_log.htm 26 | *.uvguix.* 27 | *_uvoptx.bak 28 | *_uvprojx.bak 29 | *.dep 30 | *.uvoptx 31 | *.*.bak 32 | 33 | 34 | ProjectTemplate 35 | -------------------------------------------------------------------------------- /ProjectTemplate.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/ProjectTemplate.zip -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # STM32F103DriverLib 2 | Easier way to program on STM32F103 in C++ 3 | ====== 4 | 5 | To make program on STM32 more easier, we packet every peripheral and module as a C++ class, mask operation steps instead of function-oriented interface. 6 | 7 | > eg: How to use USART to send data 8 | ```cpp 9 | # include "USART.h" 10 | USART com(1,115200); 11 | void main() 12 | { 13 | com<<"test string\r\n"; 14 | } 15 | ``` 16 | -------------------------------------------------------------------------------- /libraries/Application/AttitudeControl/AttitudeControl.cpp: -------------------------------------------------------------------------------- 1 | #include "AttitudeControl.h" 2 | 3 | 4 | 5 | AttitudeControl::AttitudeControl(Remoter &rc,AHRS &ahrs, Servo &servo) 6 | :_rc(rc),_ahrs(ahrs),_servo(servo), _posLoop(_curAngle, _tagAngle, _tagAngVel) ,_velLoop(_curAngVel,_tagAngVel,_velCtrlVal) 7 | { 8 | 9 | } 10 | 11 | 12 | void AttitudeControl::UpdateSensor() 13 | { 14 | _curAngle.roll = _ahrs.Roll()*57.29577f; 15 | _curAngle.pitch = _ahrs.Pitch()*57.29577f; 16 | _curAngle.yaw = _ahrs.Yaw()*57.29577f; 17 | 18 | _curAngVel.roll = _ahrs.GetGyro().x*57.29577f; 19 | _curAngVel.pitch = _ahrs.GetGyro().y*57.29577f; 20 | _curAngVel.yaw = _ahrs.GetGyro().z*57.29577f; 21 | 22 | // _tagAngle.roll = _rc.Roll()-50; 23 | _tagAngle.pitch = (_rc.Pitch()-50.0f)/2.0f; 24 | // _tagAngle.yaw += (_rc.Yaw()-50)*0.001; 25 | 26 | // _tagAngVel.pitch = _tagAngle.pitch*3.0f; 27 | // _tagAngVel.roll = (_rc.Roll()-50.0f)*0.2f; 28 | // _tagAngVel.pitch = (_rc.Pitch()-50.0f)*2.0f; //+= _tagAngVel.pitch + 0.3f*( (_rc.Pitch()-50.0f) - _tagAngVel.pitch); 29 | // _tagAngVel.yaw = (_rc.Yaw()-50.0f)*0.2f; 30 | } 31 | 32 | void AttitudeControl::UpdateServo() 33 | { 34 | _servo.Update(_velCtrlVal); 35 | } 36 | 37 | void AttitudeControl::PositionLoop() 38 | { 39 | _posLoop.Roll(); 40 | _posLoop.Pitch(); 41 | _posLoop.Yaw(); 42 | _posLoop.Throttle(); 43 | } 44 | 45 | void AttitudeControl::VelocityLoop() 46 | { 47 | _velLoop.Roll(); 48 | _velLoop.Pitch(); 49 | _velLoop.Yaw(); 50 | _velLoop.Throttle(); 51 | } 52 | 53 | void AttitudeControl::SET_POS_PID(float kp,float ki,float kd) 54 | { 55 | _posLoop.Set_PIT_PID((float)kp,(float)ki,(float)kd); 56 | } 57 | 58 | void AttitudeControl::SET_RATE_PID(float kp,float ki,float kd) 59 | { 60 | _velLoop.Set_PIT_PID((float)kp,(float)ki,(float)kd); 61 | } 62 | 63 | float AttitudeControl::CurrentVelocityRoll() 64 | { return _curAngVel.roll; } 65 | float AttitudeControl::CurrentVelocityPitch() 66 | { return _curAngVel.pitch; } 67 | float AttitudeControl::CurrentVelocityYaw() 68 | { return _curAngVel.yaw; } 69 | float AttitudeControl::CurrentVelocityThrottle() 70 | { return _curAngVel.throttle; } 71 | float AttitudeControl::TargetVelocityRoll() 72 | { return _tagAngVel.roll;} 73 | float AttitudeControl::TargetVelocityPitch() 74 | { return _tagAngVel.pitch;} 75 | float AttitudeControl::TargetVelocityYaw() 76 | { return _tagAngVel.yaw;} 77 | float AttitudeControl::TargetVelocityThrottle() 78 | { return _tagAngVel.throttle;} 79 | 80 | float AttitudeControl::VelCtrlValueRoll() 81 | { return _velCtrlVal.roll; } 82 | float AttitudeControl::VelCtrlValuePitch() 83 | { return _velCtrlVal.pitch; } 84 | float AttitudeControl::VelCtrlValueYaw() 85 | { return _velCtrlVal.yaw; } 86 | float AttitudeControl::VelCtrlValueThrottle() 87 | { return _velCtrlVal.throttle; } 88 | 89 | float AttitudeControl::CurrentAngleRoll() 90 | { return _curAngle.roll; } 91 | float AttitudeControl::CurrentAnglePitch() 92 | { return _curAngle.pitch; } 93 | float AttitudeControl::CurrentAngleYaw() 94 | { return _curAngle.yaw; } 95 | float AttitudeControl::TargetAngleRoll() 96 | { return _tagAngle.roll; } 97 | float AttitudeControl::TargetAnglePitch() 98 | { return _tagAngle.pitch; } 99 | float AttitudeControl::TargetAngleYaw() 100 | { return _tagAngle.yaw; } 101 | 102 | 103 | -------------------------------------------------------------------------------- /libraries/Application/AttitudeControl/AttitudeControl.h: -------------------------------------------------------------------------------- 1 | #ifndef _ATTITUDE_CONTROL_H_ 2 | #define _ATTITUDE_CONTROL_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "Remoter.h" 6 | #include "AHRS.h" 7 | #include "ESCMotor.h" 8 | #include "PositionLoop.h" 9 | #include "VelocityLoop.h" 10 | #include "mathtool.h" 11 | #include "Servo.h" 12 | 13 | class AttitudeControl 14 | { 15 | public: 16 | Remoter &_rc; 17 | AHRS &_ahrs; 18 | Servo &_servo; 19 | PositionLoop _posLoop; 20 | VelocityLoop _velLoop; 21 | 22 | CraftVector _curAngle; //current angle 23 | CraftVector _tagAngle; //target angle 24 | CraftVector _curAngVel; //current angular velocity 25 | CraftVector _tagAngVel; //target angular velocity 26 | CraftVector _velCtrlVal; //control value of velocity loop 27 | public: 28 | AttitudeControl(Remoter &rc,AHRS &ahrs, Servo &servo); 29 | 30 | void UpdateSensor(); 31 | void UpdateServo(); 32 | void PositionLoop(); 33 | void VelocityLoop(); 34 | 35 | void SET_POS_PID(float kp=0,float ki=0,float kd=0); 36 | void SET_RATE_PID(float kp=0,float ki=0,float kd=0); 37 | 38 | float CurrentVelocityRoll(); 39 | float CurrentVelocityPitch(); 40 | float CurrentVelocityYaw(); 41 | float CurrentVelocityThrottle(); 42 | float TargetVelocityRoll(); 43 | float TargetVelocityPitch(); 44 | float TargetVelocityYaw(); 45 | float TargetVelocityThrottle(); 46 | 47 | float VelCtrlValueRoll(); 48 | float VelCtrlValuePitch(); 49 | float VelCtrlValueYaw(); 50 | float VelCtrlValueThrottle(); 51 | 52 | float CurrentAngleRoll(); 53 | float CurrentAnglePitch(); 54 | float CurrentAngleYaw(); 55 | float TargetAngleRoll(); 56 | float TargetAnglePitch(); 57 | float TargetAngleYaw(); 58 | }; 59 | 60 | 61 | 62 | #endif 63 | 64 | 65 | -------------------------------------------------------------------------------- /libraries/Application/PositionLoop/PositionLoop.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "PositionLoop.h" 3 | 4 | PositionLoop::PositionLoop(const CraftVector &curAngle, const CraftVector &tagAngle, CraftVector &tagAngVel) 5 | :_curAngle(curAngle),_tagAngle(tagAngle),_tagAngVel(tagAngVel) 6 | { 7 | // Kp Ki Kd dt 8 | pidPitch(7, 0.0, 0.0, 0.004, 15, 10); 9 | pidRoll(5, 0.0, 0.1, 0.002, 15, 10); 10 | pidYaw(5, 0.0, 0.1, 0.002, 15, 10); 11 | } 12 | 13 | void PositionLoop::Roll() 14 | { 15 | // _tagAngVel.roll = pidRoll.ComputePID(_tagAngle.roll - _curAngle.roll); 16 | } 17 | 18 | void PositionLoop::Pitch() 19 | { 20 | _tagAngVel.pitch = pidPitch.ComputePID(_tagAngle.pitch , _curAngle.pitch); 21 | } 22 | 23 | void PositionLoop::Yaw() 24 | { 25 | // _tagAngVel.yaw = pidYaw.ComputePID(_tagAngle.yaw - _curAngle.yaw); 26 | } 27 | 28 | void PositionLoop::Throttle() 29 | { 30 | 31 | } 32 | 33 | void PositionLoop::Set_PIT_PID(float kp, float ki, float kd) 34 | { 35 | pidPitch.Set_PID(kp, ki, kd); 36 | } 37 | 38 | void PositionLoop::Set_ROL_PID(float kp, float ki, float kd) 39 | { 40 | pidRoll.Set_PID(kp, ki, kd); 41 | } 42 | 43 | void PositionLoop::Set_YAW_PID(float kp, float ki, float kd) 44 | { 45 | pidYaw.Set_PID(kp, ki, kd); 46 | } 47 | 48 | -------------------------------------------------------------------------------- /libraries/Application/PositionLoop/PositionLoop.h: -------------------------------------------------------------------------------- 1 | #ifndef _POSITION_LOOP_H_ 2 | #define _POSITION_LOOP_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "mathtool.h" 6 | #include "PIDParameter.h" 7 | 8 | class PositionLoop 9 | { 10 | private: 11 | const CraftVector &_curAngle; //current angle 12 | const CraftVector &_tagAngle; //target angle 13 | CraftVector &_tagAngVel; //target angular velocity 14 | 15 | PIDParameter pidRoll; 16 | PIDParameter pidPitch; 17 | PIDParameter pidYaw; 18 | PIDParameter pidThrottle; 19 | public: 20 | PositionLoop(const CraftVector &curAngle, const CraftVector &tagAngle, CraftVector &tagAngVel); 21 | 22 | void Roll(); 23 | void Pitch(); 24 | void Yaw(); 25 | void Throttle(); 26 | 27 | void Set_PIT_PID(float kp=0, float ki=0, float kd=0); 28 | void Set_ROL_PID(float kp=0, float ki=0, float kd=0); 29 | void Set_YAW_PID(float kp=0, float ki=0, float kd=0); 30 | }; 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | #endif 42 | -------------------------------------------------------------------------------- /libraries/Application/Servo/Servo.cpp: -------------------------------------------------------------------------------- 1 | #include "Servo.h" 2 | 3 | 4 | 5 | Servo::Servo(ESCMotor *m1,ESCMotor *m2,ESCMotor *m3,ESCMotor *m4) 6 | { 7 | _motor[0] = m1; 8 | _motor[1] = m2; 9 | _motor[2] = m3; 10 | _motor[3] = m4; 11 | 12 | _factor[0].roll = -1; _factor[0].pitch = 1; _factor[0].yaw = -1; _factor[0].throttle = 1; 13 | _factor[1].roll = 1; _factor[1].pitch = 1; _factor[1].yaw = 1; _factor[1].throttle = 1; 14 | _factor[2].roll = 1; _factor[2].pitch = -1; _factor[2].yaw = -1; _factor[2].throttle = 1; 15 | _factor[3].roll = -1; _factor[3].pitch = -1; _factor[3].yaw = 1; _factor[3].throttle = 1; 16 | } 17 | 18 | 19 | void Servo::SetDutyRange(float maxDuty,float minDuty) 20 | { 21 | for(int i=0;i<4;i++) 22 | _motor[i]->SetDutyRange(maxDuty,minDuty); 23 | } 24 | void Servo::FullSpeed() 25 | { 26 | for(int i=0;i<4;i++) 27 | _motor[i]->Speed(100); 28 | } 29 | void Servo::Stop() 30 | { 31 | for(int i=0;i<4;i++) 32 | _motor[i]->Speed(0); 33 | } 34 | 35 | void Servo::Update(const CraftVector &ctrlVal) 36 | { 37 | for(u8 i=0;i<4;i++) 38 | { 39 | _speed[i] = _factor[i].roll*ctrlVal.roll + _factor[i].pitch*ctrlVal.pitch + _factor[i].yaw*ctrlVal.yaw + _factor[i].throttle*ctrlVal.throttle; 40 | if(_speed[i]<0) 41 | _speed[i] = 0; 42 | if(_speed[i]>20) 43 | _speed[i] = 20; 44 | _motor[i]->Speed(_speed[i]+15); 45 | } 46 | } 47 | 48 | 49 | 50 | 51 | -------------------------------------------------------------------------------- /libraries/Application/Servo/Servo.h: -------------------------------------------------------------------------------- 1 | #ifndef _SERVO_H_ 2 | #define _SERVO_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "ESCMotor.h" 6 | #include "mathtool.h" 7 | 8 | 9 | // 3 back 4 10 | // O O 11 | // \ / 12 | // \ / 13 | // \ / 14 | // X 15 | // / \ 16 | // / \ 17 | // / \ 18 | // O O 19 | // 2 front 1 20 | 21 | class Servo 22 | { 23 | private: 24 | ESCMotor *_motor[4]; 25 | float _speed[4]; 26 | CraftVector _factor[4]; 27 | public: 28 | Servo(ESCMotor *m1,ESCMotor *m2,ESCMotor *m3,ESCMotor *m4); 29 | void SetDutyRange(float maxDuty,float minDuty); 30 | void FullSpeed(); 31 | void Stop(); 32 | 33 | void Update(const CraftVector &velCtrlValue); 34 | }; 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | #endif 43 | 44 | -------------------------------------------------------------------------------- /libraries/Application/VelocityLoop/VelocityLoop.cpp: -------------------------------------------------------------------------------- 1 | #include "VelocityLoop.h" 2 | 3 | 4 | VelocityLoop::VelocityLoop(const CraftVector &curAngVel, const CraftVector &tagAngVel, CraftVector &velCtrlVal) 5 | :_curAngVel(curAngVel),_tagAngVel(tagAngVel),_velCtrlVal(velCtrlVal) 6 | { 7 | // Kp Ki Kd dt 8 | pidPitch(5, 0.0, 0.1, 0.002, 15, 10); 9 | pidRoll(5, 0.0, 0.1, 0.002, 15, 10); 10 | pidYaw(5, 0.0, 0.1, 0.002, 15, 10); 11 | } 12 | 13 | void VelocityLoop::Roll() 14 | { 15 | // _velCtrlVal.roll = pidRoll.ComputePID(_tagAngVel.roll, _curAngVel.roll); 16 | } 17 | 18 | void VelocityLoop::Pitch() 19 | { 20 | _velCtrlVal.pitch = pidPitch.ComputePID(_tagAngVel.pitch, _curAngVel.pitch); 21 | } 22 | 23 | void VelocityLoop::Yaw() 24 | { 25 | // _velCtrlVal.yaw = pidYaw.ComputePID(_tagAngVel.yaw, _curAngVel.yaw); 26 | } 27 | 28 | void VelocityLoop::Throttle() 29 | { 30 | 31 | } 32 | 33 | void VelocityLoop::Set_PIT_PID(float kp, float ki, float kd) 34 | { 35 | pidPitch.Set_PID(kp, ki, kd); 36 | } 37 | 38 | void VelocityLoop::Set_ROL_PID(float kp, float ki, float kd) 39 | { 40 | pidRoll.Set_PID(kp, ki, kd); 41 | } 42 | 43 | void VelocityLoop::Set_YAW_PID(float kp, float ki, float kd) 44 | { 45 | pidYaw.Set_PID(kp, ki, kd); 46 | } 47 | 48 | -------------------------------------------------------------------------------- /libraries/Application/VelocityLoop/VelocityLoop.h: -------------------------------------------------------------------------------- 1 | #ifndef _VELOCITY_LOOP_H_ 2 | #define _VELOCITY_LOOP_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "mathtool.h" 6 | #include "PIDParameter.h" 7 | 8 | class VelocityLoop 9 | { 10 | private: 11 | const CraftVector &_curAngVel; //current angular velocity 12 | const CraftVector &_tagAngVel; //target angular velocity 13 | CraftVector &_velCtrlVal; //control value of velocity loop 14 | 15 | PIDParameter pidRoll; 16 | PIDParameter pidPitch; 17 | PIDParameter pidYaw; 18 | PIDParameter pidThrottle; 19 | public: 20 | VelocityLoop(const CraftVector &curAngVel, const CraftVector &tagAngVel, CraftVector &velCtrlVal); 21 | 22 | void Roll(); 23 | void Pitch(); 24 | void Yaw(); 25 | void Throttle(); 26 | 27 | void Set_PIT_PID(float kp=0, float ki=0, float kd=0); 28 | void Set_ROL_PID(float kp=0, float ki=0, float kd=0); 29 | void Set_YAW_PID(float kp=0, float ki=0, float kd=0); 30 | 31 | void Set_RATE_PIT_PID(float kp=0, float ki=0, float kd=0); 32 | void Set_RATE_ROL_PID(float kp=0, float ki=0, float kd=0); 33 | void Set_RATE_YAW_PID(float kp=0, float ki=0, float kd=0); 34 | }; 35 | 36 | 37 | 38 | 39 | 40 | 41 | #endif 42 | -------------------------------------------------------------------------------- /libraries/OffChip/AHRS/AHRS.h: -------------------------------------------------------------------------------- 1 | #ifndef _AHRS_H_ 2 | #define _AHRS_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "InertialSensor.h" 6 | #include "Compass.h" 7 | #include "Barometer.h" 8 | 9 | class AHRS 10 | { 11 | protected: 12 | InertialSensor &_ins; //inertial sensor 13 | Compass *_compass; //compass 14 | Barometer *_baro; //barometer 15 | 16 | Vector3f _acc; //3-aixs acceleration data 17 | Vector3f _gyro; //3-aixs gyroscope data 18 | Vector3f _mag; //3-aixs compass magnetic 19 | float _pressure; //air pressure 20 | 21 | float _roll; 22 | float _pitch; 23 | float _yaw; 24 | //Quaternion _q; //quternion: q1,q2,q3,q4 25 | public: 26 | AHRS(InertialSensor &ins,Compass *compass=0, Barometer *baro=0):_ins(ins),_compass(compass),_baro(baro){}; 27 | virtual bool Update()=0; //update inertial sensor data 28 | Vector3f GetAcc() {return _acc; } // get acceleration data 29 | Vector3f GetGyro() {return _gyro;} //get gyroscope data 30 | Vector3f GetMag() {return _mag;} 31 | float GetPressure(){return _pressure;} 32 | float Roll() { return _roll; } 33 | float Pitch() { return _pitch;} 34 | float Yaw() { return _yaw;} 35 | virtual bool Ready()=0; 36 | }; 37 | 38 | #endif 39 | 40 | -------------------------------------------------------------------------------- /libraries/OffChip/AHRS/AHRS_DCM.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "AHRS_DCM.h" 3 | 4 | #include "USART.h" 5 | extern USART com; 6 | 7 | AHRS_DCM::AHRS_DCM(InertialSensor &ins,Compass *compass, Barometer *baro):AHRS(ins,compass,baro) 8 | { 9 | _omega.Zero(); 10 | _omega_I.Zero(); 11 | _omega_P.Zero(); 12 | _omega_yaw.Zero(); 13 | _dcm_matrix.Identity(); 14 | } 15 | 16 | bool AHRS_DCM::Update() 17 | { 18 | static u8 cnt = 0; 19 | 20 | if(_ins.Update(_acc,_gyro)) 21 | { 22 | UpdateMatrix(); 23 | if(++cnt>10) 24 | { 25 | cnt = 0; 26 | DriftCorrection(); 27 | } 28 | } 29 | if(_compass) _compass->Update(_mag); 30 | if(_baro) _baro->Update(_pressure); 31 | return true; 32 | } 33 | void AHRS_DCM::UpdateMatrix() 34 | { 35 | Vector3f delta = (_gyro + _omega_I + _omega_P + _omega_yaw)*0.002; 36 | _dcm_matrix.Rotate(delta); 37 | _dcm_matrix.Normalize(); 38 | _dcm_matrix.ToEuler(&_roll,&_pitch,&_yaw); 39 | } 40 | void AHRS_DCM::DriftCorrection() 41 | { 42 | Matrix3 temp_dcm = _dcm_matrix; 43 | 44 | Vector3f GA_b = temp_dcm * _acc; 45 | //com< _dcm_matrix; 12 | Vector3f _omega; 13 | Vector3f _omega_I; 14 | Vector3f _omega_P; 15 | Vector3f _omega_yaw; 16 | Vector3f _acc_ef; 17 | Vector3f _ra_sum; 18 | float _ra_deltat; 19 | 20 | public: 21 | AHRS_DCM(InertialSensor &ins,Compass *compass=0, Barometer *baro=0); 22 | virtual bool Update(); 23 | virtual bool Ready(); 24 | void UpdateMatrix(); 25 | void DriftCorrection(); 26 | }; 27 | 28 | #endif 29 | 30 | -------------------------------------------------------------------------------- /libraries/OffChip/BLDCMotor/BLDCMotor.cpp: -------------------------------------------------------------------------------- 1 | #include "BLDCMotor.h" 2 | 3 | bool BLDCMotor::bInitSPWM = false; 4 | float BLDCMotor::SPWM[256] = {0}; 5 | 6 | 7 | void BLDCMotor::InitSPWM() 8 | { 9 | for(int i=0;i<256;i++) 10 | { 11 | SPWM[i] = sin(i*2.0*3.1415926/256.0); 12 | } 13 | } 14 | 15 | BLDCMotor::BLDCMotor(PWM *pwma, u8 cha, PWM *pwmb, u8 chb, PWM *pwmc, u8 chc, float power) 16 | { 17 | _pwm_a = pwma; 18 | _pwm_b = pwmb; 19 | _pwm_c = pwmc; 20 | _ch_a = cha; 21 | _ch_b = chb; 22 | _ch_c = chc; 23 | _maxPower = power; 24 | _armed = false; 25 | if(bInitSPWM) return; 26 | bInitSPWM = true; 27 | InitSPWM(); 28 | } 29 | 30 | void BLDCMotor::Initialize(PWM *pwma, u8 cha, PWM *pwmb, u8 chb, PWM *pwmc, u8 chc, float power) 31 | { 32 | _pwm_a = pwma; 33 | _pwm_b = pwmb; 34 | _pwm_c = pwmc; 35 | _ch_a = cha; 36 | _ch_b = chb; 37 | _ch_c = chc; 38 | _maxPower = power; 39 | 40 | } 41 | 42 | 43 | void BLDCMotor::SetPosition(int position) 44 | { 45 | if(!_armed) return; 46 | float a,b,c; 47 | 48 | u16 pos = position & 0xFF; 49 | 50 | a = SPWM[pos%256]; 51 | b = SPWM[(pos+85)%256]; 52 | c = SPWM[(pos+170)%256]; 53 | 54 | a = (_maxPower*a + 1.0)/2.0; 55 | b = (_maxPower*b + 1.0)/2.0; 56 | c = (_maxPower*c + 1.0)/2.0; 57 | 58 | _pwm_a->SetDuty(_ch_a,a*100); 59 | _pwm_b->SetDuty(_ch_b,b*100); 60 | _pwm_c->SetDuty(_ch_c,c*100); 61 | } 62 | void BLDCMotor::Enable() 63 | { 64 | _armed = true; 65 | } 66 | void BLDCMotor::Disable() 67 | { 68 | _armed = false; 69 | _pwm_a->SetDuty(_ch_a,0); 70 | _pwm_b->SetDuty(_ch_b,0); 71 | _pwm_c->SetDuty(_ch_c,0); 72 | } 73 | 74 | 75 | 76 | -------------------------------------------------------------------------------- /libraries/OffChip/BLDCMotor/BLDCMotor.h: -------------------------------------------------------------------------------- 1 | #ifndef __BLDCMOTOR_H 2 | #define __BLDCMOTOR_H 3 | #include "PWM.h" 4 | #include "math.h" 5 | 6 | class BLDCMotor 7 | { 8 | private: 9 | static bool bInitSPWM; 10 | static float SPWM[256]; 11 | PWM *_pwm_a; 12 | PWM *_pwm_b; 13 | PWM *_pwm_c; 14 | u8 _ch_a; 15 | u8 _ch_b; 16 | u8 _ch_c; 17 | float _maxPower; 18 | bool _armed; 19 | private: 20 | static void InitSPWM(); 21 | public: 22 | BLDCMotor(PWM *pwma, u8 cha, PWM *pwmb, u8 chb, PWM *pwmc, u8 chc, float power); 23 | void Initialize(PWM *pwma, u8 cha, PWM *pwmb, u8 chb, PWM *pwmc, u8 chc, float power); 24 | void SetPosition(int pos); 25 | void Enable(); 26 | void Disable(); 27 | }; 28 | 29 | #endif 30 | 31 | -------------------------------------------------------------------------------- /libraries/OffChip/Barometer/Barometer.h: -------------------------------------------------------------------------------- 1 | #ifndef _BAROMETER_H_ 2 | #define _BAROMETER_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "Sensor.h" 6 | 7 | class Barometer: public Sensor 8 | { 9 | public: 10 | virtual bool Initialize()=0; 11 | virtual bool Update(float &pressure)=0; 12 | }; 13 | 14 | #endif 15 | 16 | -------------------------------------------------------------------------------- /libraries/OffChip/Barometer/MS561101.cpp: -------------------------------------------------------------------------------- 1 | #include "MS561101.h" 2 | #include "TaskManager.h" 3 | 4 | MS561101::MS561101(I2C &i2c):mI2C(i2c) 5 | { 6 | Initialize(); 7 | } 8 | 9 | 10 | bool MS561101::Initialize() 11 | { 12 | mConvertPressure = false; //Convert temperature fisrt 13 | mHealthy = false; //set MS561101 not healthy 14 | if(!mI2C.WaitFree(50)) //wait for i2c work and free 15 | if(!mI2C.Initialize()) return false; //if time out, reset and initialize i2c 16 | 17 | u8 cmd = MS561101BA_RESET; 18 | mI2C.AddCommand(MS561101BA_ADDR, &cmd, 1, 0, 0, this, true); //reset ms561101 19 | if(!mI2C.Start()) return false; //start to rum i2c command 20 | if(!mI2C.WaitFree(50)) return false; 21 | for(volatile u32 i=0; i<500000;i++); 22 | 23 | for(u8 i=0; i<6; i++) //read rom data of ms561101 24 | { 25 | bool isTaskTail = ((i==5) ? true : false); 26 | cmd = MS561101BA_PROM_BASE_ADDR + i*2; 27 | //Get Rom data: i2c addr txdata txNum rxdata[] rxNum 28 | mI2C.AddCommand(MS561101BA_ADDR, &cmd, 1, mRomData+i*2, 2, this, isTaskTail); 29 | } 30 | if(!mI2C.Start()) return false; //start to rum i2c command 31 | if(!mI2C.WaitFree(50)) return false; //wait MS5611 initialize complete, if time out, keep nuhealthy state 32 | mHealthy = true; //initialize success 33 | for(u8 i=0;i<6;i++) 34 | mC[i] = u16((mRomData[i*2]<<8) | mRomData[i*2+1]); //Calculate C1,C2,C3,C4,C5,C6 35 | return true; 36 | } 37 | 38 | bool MS561101::Update(float &pressure) 39 | { 40 | static double curTime; 41 | curTime = tskmgr.Time(); 42 | if(!mI2C.IsHealthy()) //if i2c not work correctly 43 | { 44 | mI2C.Initialize(); //initialize i2c 45 | Initialize(); //initialize MS561101 46 | return false; 47 | } 48 | if(mIsUpdated==false) 49 | { 50 | if(curTime- mUpdatedTime > 1) 51 | { 52 | mI2C.Initialize(); //initialize i2c 53 | Initialize(); //initialize MS561101 54 | mIsUpdated = true; 55 | } 56 | return false; 57 | } 58 | if(curTime-mUpdatedTime<0.01) return false; //minimal interval > 10ms = 0.01s 59 | 60 | mIsUpdated = false; 61 | 62 | static u8 cmd[3] = {0,MS561101BA_D1+MS561101BA_OSR_4096,MS561101BA_D2+MS561101BA_OSR_4096}; 63 | if(mConvertPressure) 64 | { 65 | mI2C.AddCommand(MS561101BA_ADDR, cmd, 1, mRawT, 3, this, false); //read temperature data 66 | mI2C.AddCommand(MS561101BA_ADDR, cmd+1, 1, 0, 0, this, true); //read temperature data 67 | } 68 | else 69 | { 70 | mI2C.AddCommand(MS561101BA_ADDR, cmd, 1, mRawP, 3, this, false); //read pressure data 71 | mI2C.AddCommand(MS561101BA_ADDR, cmd+2, 1, 0, 0, this, true); //read temperature data 72 | } 73 | mConvertPressure = !mConvertPressure; 74 | 75 | pressure = Pressure(); 76 | 77 | return true; 78 | } 79 | 80 | float MS561101::Temperature() 81 | { 82 | static int64_t deltaT; 83 | static int32_t temperature; 84 | deltaT = int32_t(((u32)(mRawT[0]<<16))|((u32)(mRawT[1])<<8)|mRawT[2]) - u32(mC[4]<<8); 85 | temperature = 2000 + ((deltaT*mC[5])>>23); 86 | if(temperature<2000) 87 | temperature = temperature - ((deltaT*deltaT)>>31); 88 | return temperature/100.0f; 89 | } 90 | float MS561101::Pressure() 91 | { 92 | int64_t OFF2=0; 93 | int64_t SENS2=0; 94 | int64_t dT = ((u32)(mRawT[0]<<16)|(u32)(mRawT[1]<<8)|mRawT[2]) - (mC[4]<<8 ); 95 | int64_t OFF =(int64_t(mC[1])<<16) + ((int64_t(mC[3]*dT))>>7); 96 | int64_t SENS=((int64_t)(mC[0])<<15) + ( ((int64_t)(mC[2])*dT) >>8 ); 97 | int32_t TEMP=2000 + ((dT*(mC[5]))>>23); 98 | 99 | //SECOND ORDER TEMPERATURE COMPENSATION 100 | if(TEMP<2000) 101 | { 102 | OFF2=(5*(TEMP-2000)*(TEMP-2000))>>1; 103 | SENS2=(5*(TEMP-2000)*(TEMP-2000))>>2; 104 | if(TEMP<-1500) 105 | { 106 | OFF2 = OFF2 + 7*(TEMP+1500)*(TEMP+1500); 107 | SENS2 = SENS2 + ((11*(TEMP+1500)*(TEMP+1500))>>1); 108 | } 109 | } 110 | OFF -= OFF2; 111 | SENS -= SENS2; 112 | return (((((mRawP[0]<<16|mRawP[1]<<8|mRawP[2]) *SENS) >>21) - OFF)>>15)/100.0f; 113 | } 114 | 115 | -------------------------------------------------------------------------------- /libraries/OffChip/Barometer/MS561101.h: -------------------------------------------------------------------------------- 1 | #ifndef _MS561101_H_ 2 | #define _MS561101_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "Barometer.h" 6 | #include "I2C.h" 7 | 8 | class MS561101: public Barometer 9 | { 10 | protected: 11 | I2C &mI2C; 12 | u8 mRomData[12]; 13 | u16 mC[6]; 14 | bool mConvertPressure; 15 | u8 mRawT[3]; 16 | u8 mRawP[3]; 17 | public: 18 | MS561101(I2C &i2c); 19 | virtual bool Initialize(); 20 | virtual bool Update(float &pressure); 21 | float Temperature(); 22 | float Pressure(); 23 | }; 24 | 25 | //#define MS561101BA_Pin_CSB_HIGH 26 | 27 | #ifdef MS561101BA_Pin_CSB_HIGH 28 | #define MS561101BA_ADDR 0xEC 29 | #else 30 | #define MS561101BA_ADDR 0xEE 31 | #endif 32 | 33 | 34 | // registers of the device 35 | #define MS561101BA_D1 0x40 36 | #define MS561101BA_D2 0x50 37 | #define MS561101BA_RESET 0x1E 38 | #define MS561101BA_D1D2_SIZE 3 // D1 and D2 result size (bytes) 39 | 40 | // OSR (Over Sampling Ratio) constants 41 | #define MS561101BA_OSR_256 0x00 42 | #define MS561101BA_OSR_512 0x02 43 | #define MS561101BA_OSR_1024 0x04 44 | #define MS561101BA_OSR_2048 0x06 45 | #define MS561101BA_OSR_4096 0x08 46 | 47 | #define MS561101BA_PROM_BASE_ADDR 0xA2 // by adding ints from 0 to 6 we can read all the prom configuration values. 48 | // C1 will be at 0xA2 and all the subsequent are multiples of 2 49 | #define MS561101BA_PROM_REG_COUNT 6 // number of registers in the PROM 50 | #define MS561101BA_PROM_REG_SIZE 2 // size in bytes of a prom registry. 51 | 52 | #endif 53 | 54 | 55 | 56 | 57 | -------------------------------------------------------------------------------- /libraries/OffChip/Compass/Compass.h: -------------------------------------------------------------------------------- 1 | #ifndef _COMPASS_H_ 2 | #define _COMPASS_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "Mathtool.h" 6 | #include "Sensor.h" 7 | 8 | class Compass : public Sensor 9 | { 10 | protected: 11 | bool _mag_calibrating; 12 | Vector3f mOffsetRatio; 13 | Vector3f mOffsetBias; 14 | unsigned char mHealth; 15 | public: 16 | virtual bool Initialize()=0; 17 | virtual bool Update(Vector3f &mag)=0; 18 | 19 | void StartMagCalibrating(){_mag_calibrating = true;} 20 | void StopMagCalibrating(){_mag_calibrating = false;} 21 | bool MagCalibrating(){ return _mag_calibrating;} 22 | 23 | void SetOffsetBias(Vector3f bias){ mOffsetBias = bias;} 24 | Vector3f GetOffsetBias(){ return mOffsetBias;} 25 | 26 | void SetOffsetRatio(Vector3f ratio){ mOffsetRatio = ratio;} 27 | Vector3f GetOffsetRatio(){ return mOffsetRatio;} 28 | }; 29 | 30 | 31 | #endif 32 | 33 | -------------------------------------------------------------------------------- /libraries/OffChip/DHT12/DHT12.cpp: -------------------------------------------------------------------------------- 1 | #include "DHT12.h" 2 | 3 | DHT12::DHT12() 4 | { 5 | IIC_Init(); 6 | V_Temper = 0; 7 | V_Humid = 0; 8 | } 9 | 10 | void DHT12::DHT12_ReadByte(void) 11 | { 12 | uint8_t i; 13 | 14 | IIC_Start(); 15 | IIC_Send_Byte(0xB8); 16 | IIC_Wait_Ack( ); 17 | 18 | IIC_Send_Byte(0x00); 19 | IIC_Wait_Ack( ); 20 | 21 | IIC_Start( ); 22 | IIC_Send_Byte(0xB9); 23 | IIC_Wait_Ack( ); 24 | 25 | for(i = 0; i < 4; i++) 26 | { 27 | readData[i] = IIC_Read_Byte(1); 28 | } 29 | readData[i] = IIC_Read_Byte(0); 30 | 31 | IIC_Stop(); 32 | } 33 | 34 | void DHT12::Update(void) 35 | { 36 | DHT12_ReadByte(); 37 | bool isChecked = false; 38 | if(readData[4] == (readData[0] + readData[1] + readData[2] + readData[3])) 39 | isChecked = true; 40 | else 41 | isChecked = false; 42 | 43 | if(isChecked) { 44 | V_Humid = ((readData[0] + readData[1]/10.0)); 45 | if(readData[3]&0x80) 46 | V_Temper = -(readData[2] + (readData[3]/10.0)); 47 | else 48 | V_Temper = (readData[2] + (readData[3]/10.0)); 49 | } 50 | } 51 | 52 | uint16_t DHT12::GetHumid(void) 53 | { 54 | return V_Humid; 55 | } 56 | 57 | uint16_t DHT12::GetTemper(void) 58 | { 59 | return V_Temper; 60 | } 61 | -------------------------------------------------------------------------------- /libraries/OffChip/DHT12/DHT12.h: -------------------------------------------------------------------------------- 1 | #ifndef _DHT21_H_ 2 | #define _DHT21_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "SoftwareI2C.h" 6 | #include "I2C.h" 7 | 8 | #define DHT12_ADDRESS 0xB8 9 | 10 | class DHT12:public Sensor{ 11 | 12 | private: 13 | float V_Humid; 14 | float V_Temper; 15 | uint8_t readData[5]; 16 | public: 17 | DHT12(); 18 | void Update(void); 19 | void DHT12_ReadByte(void); 20 | uint16_t GetHumid(void); 21 | uint16_t GetTemper(void); 22 | }; 23 | 24 | #endif 25 | -------------------------------------------------------------------------------- /libraries/OffChip/ESCMotor/ESCMotor.cpp: -------------------------------------------------------------------------------- 1 | #include "ESCMotor.h" 2 | 3 | 4 | ESCMotor::ESCMotor(PWM &tim, u8 ch):_tim(tim),_ch(ch) 5 | { 6 | 7 | } 8 | void ESCMotor::SetDutyRange(float maxDuty, float minDuty) 9 | { 10 | _maxDuty = maxDuty; 11 | _minDuty = minDuty; 12 | } 13 | 14 | void ESCMotor::Speed(float VelocityRate) 15 | { 16 | _tim.SetDuty(_ch, _minDuty + VelocityRate*(_maxDuty - _minDuty)/100.0f); 17 | } 18 | 19 | 20 | -------------------------------------------------------------------------------- /libraries/OffChip/ESCMotor/ESCMotor.h: -------------------------------------------------------------------------------- 1 | #ifndef _ESC_MOTOR_H_ 2 | #define _ESC_MOTOR_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "PWM.h" 6 | 7 | 8 | class ESCMotor 9 | { 10 | private: 11 | PWM &_tim; 12 | u8 _ch; 13 | float _maxDuty; //0.0% ~ 100.0% 14 | float _minDuty; //0.0% ~ 100.0% 15 | float _speed; //0.0% ~ 100.0% 16 | public: 17 | ESCMotor(PWM &tim,u8 ch); 18 | void SetDutyRange(float maxDuty, float minDuty); 19 | void Speed(float rate); 20 | 21 | }; 22 | 23 | 24 | 25 | 26 | #endif 27 | 28 | 29 | -------------------------------------------------------------------------------- /libraries/OffChip/GPRS/GPRS.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/GPRS/GPRS.cpp -------------------------------------------------------------------------------- /libraries/OffChip/GPRS/GPRS.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/GPRS/GPRS.h -------------------------------------------------------------------------------- /libraries/OffChip/Gimbal/Gimbal.cpp: -------------------------------------------------------------------------------- 1 | #include "Gimbal.h" 2 | #include "TaskManager.h" 3 | #include "math.h" 4 | #include "USART.h" 5 | extern USART com; 6 | 7 | Gimbal::Gimbal(AHRS &ahrs, StepMotor &motorRoll,StepMotor &motorPitch,StepMotor &motorYaw, u16 ctrlHz):_ahrs(ahrs), _motor_roll(motorRoll),_motor_pitch(motorPitch),_motor_yaw(motorYaw) 8 | { 9 | _ctrlHz = ctrlHz; 10 | _DTms = 1000.0/_ctrlHz; 11 | 12 | _roll = 0; 13 | _pitch = 0; 14 | _yaw = 0; 15 | _yaw_vel = 0; 16 | _yaw_pulse = 0; 17 | 18 | _targetRoll = 0; 19 | _targetPitch = 0; 20 | _targetYaw = 0; 21 | 22 | 23 | _adc_yaw = 0; 24 | _remoter = 0; 25 | 26 | // _rollPID(1000,4,13); 27 | // _pitchPID(1000,4,8); 28 | // _yawPID(-0,-0.001,-0.00); 29 | } 30 | 31 | double Gimbal::UpdateIMU() 32 | { 33 | double enterTime = tskmgr.Time(); 34 | 35 | _ahrs.Update(); 36 | 37 | _roll = _ahrs.Roll(); 38 | _pitch = _ahrs.Pitch(); 39 | 40 | if(_adc_yaw) 41 | { 42 | float newYaw = ((*_adc_yaw)[_adc_yaw_ch]-1.35f)*90.0f / 0.70f; 43 | _yaw = _yaw + (newYaw-_yaw)*0.1; 44 | } 45 | Vector3f gyro = _ahrs.GetGyro(); 46 | 47 | _yaw_vel = cos(_roll)*cos(_pitch)*gyro.z - gyro.y*sin(_roll) - gyro.x*cos(_roll)*sin(_pitch);//+= 0.1*(_ahrs.GetGyro().z - _yaw_vel); 48 | 49 | return (tskmgr.Time()-enterTime)*1000; 50 | } 51 | double Gimbal::UpdateRC() 52 | { 53 | double enterTime = tskmgr.Time(); 54 | 55 | if(_remoter) 56 | { 57 | _remoter->Update(); 58 | 59 | if(!_remoter->Ready()) return (tskmgr.Time()-enterTime)*1000; 60 | 61 | float pitchSpeed = (*_remoter)[1]-50; 62 | float yawSpeed = (*_remoter)[2]-50; 63 | float rollSpeed = (*_remoter)[3]-50; 64 | 65 | pitchSpeed = (abs(pitchSpeed)>8 ? pitchSpeed:0); 66 | yawSpeed = (abs(yawSpeed) >8 ? yawSpeed :0); 67 | rollSpeed = (abs(rollSpeed) >8 ? rollSpeed :0); 68 | 69 | _targetPitch += 0.006f*pitchSpeed*_DTms / 1000.0f; //pitch 70 | 71 | _targetRoll += 0.003f*rollSpeed*_DTms / 1000.0f; //roll 72 | 73 | float deltaYaw = 0.8f*yawSpeed*_DTms / 1000.0f; //yaw 74 | _targetYaw += deltaYaw; 75 | _yaw_pulse += 4.2f*deltaYaw; 76 | } 77 | 78 | return (tskmgr.Time()-enterTime)*1000; 79 | } 80 | 81 | double Gimbal::UpdateMotor() 82 | { 83 | double enterTime = tskmgr.Time(); 84 | 85 | _motor_roll.SetPosition(_rollPID.ComputePID(_targetRoll,_roll)); 86 | _motor_pitch.SetPosition(_pitchPID.ComputePID(_targetPitch,_pitch)); 87 | if(_adc_yaw) 88 | { 89 | 90 | _motor_yaw.SetPosition(-_yawPID.ComputePID(_targetYaw,_yaw)-_yaw_vel*150 + _yaw_pulse); 91 | } 92 | return (tskmgr.Time()-enterTime)*1000; 93 | } 94 | 95 | void Gimbal::SetYaw(ADC *adc,u16 yawCh) 96 | { 97 | _adc_yaw = adc; 98 | _adc_yaw_ch = yawCh; 99 | } 100 | void Gimbal::SetRemoter(Remoter_PWM_EXIT *rc) 101 | { 102 | _remoter = rc; 103 | } 104 | 105 | float Gimbal::Roll() //get roll angle 106 | { 107 | return _roll*57.29f; 108 | } 109 | float Gimbal::Pitch() //get pitch angle 110 | { 111 | return _pitch*57.29f; 112 | } 113 | 114 | float Gimbal::Yaw() //get yaw angle 115 | { 116 | return _yaw; 117 | } 118 | 119 | float Gimbal::TargetRoll() //get target roll angle 120 | { 121 | return _targetRoll; 122 | } 123 | float Gimbal::TargetPitch() //get target pitch angle 124 | { 125 | return _targetPitch; 126 | } 127 | float Gimbal::TargetYaw() //get target yaw angle 128 | { 129 | return _targetYaw; 130 | } 131 | 132 | void Gimbal::SetRollPID(float Kp,float Ki, float Kd) //set pid parameters of roll 133 | { 134 | // _rollPID(Kp,Ki,Kd); 135 | } 136 | void Gimbal::SetPitchPID(float Kp,float Ki, float Kd) //set pid parameters of pitch 137 | { 138 | // _pitchPID(Kp,Ki,Kd); 139 | } 140 | void Gimbal::SetYawPID(float Kp,float Ki, float Kd) //set pid parameters of yaw 141 | { 142 | // _yawPID(Kp,Ki,Kd); 143 | } 144 | 145 | void Gimbal::Arm() 146 | { 147 | _motor_roll.Enable(); 148 | _motor_pitch.Enable(); 149 | _motor_yaw.Enable(); 150 | } 151 | void Gimbal::DisArm() 152 | { 153 | _motor_roll.Disable(); 154 | _motor_pitch.Disable(); 155 | _motor_yaw.Disable(); 156 | } 157 | -------------------------------------------------------------------------------- /libraries/OffChip/Gimbal/Gimbal.h: -------------------------------------------------------------------------------- 1 | #ifndef _GIMBAL_H_ 2 | #define _GIMBAL_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "StepMotor.h" 6 | #include "AHRS.h" 7 | #include "PIDParameter.h" 8 | #include "ADC.h" 9 | #include "Remoter_PWM_EXIT.h" 10 | 11 | class Gimbal 12 | { 13 | private: 14 | AHRS &_ahrs; //AHRS 15 | StepMotor &_motor_roll; //Roll Motor 16 | StepMotor &_motor_pitch; //Pitch Motor 17 | StepMotor &_motor_yaw; //Pitch Motor 18 | ADC *_adc_yaw; //adc object for yaw 19 | u16 _adc_yaw_ch; //adc channel for yaw 20 | Remoter_PWM_EXIT* _remoter; //remoter 21 | 22 | float _DTms; //delta time since last control / update (unit: ms) 23 | u16 _ctrlHz; //control frequence 24 | float _roll; //roll angle of imu 25 | float _pitch; //pitch angle of imu 26 | float _yaw; //yaw angle of imu 27 | 28 | float _yaw_vel; //yaw velocity 29 | float _yaw_pulse; 30 | 31 | float _targetRoll; //target angle of roll 32 | float _targetPitch; //target angle of pitch 33 | float _targetYaw; //target angle of yaw 34 | PIDParameter _rollPID; 35 | PIDParameter _pitchPID; 36 | PIDParameter _yawPID; 37 | public: 38 | Gimbal(AHRS &ahrs, StepMotor &motorRoll, StepMotor &motorPitch,StepMotor &motorYaw, u16 ctrlHz=500); 39 | void SetYaw(ADC *adc,u16 yawCh); 40 | void SetRemoter(Remoter_PWM_EXIT *rc); 41 | double UpdateIMU(); //update _roll,_pitch,_yaw 42 | double UpdateRC(); //update _targetRoll, _targetPitch, targetYaw 43 | double UpdateMotor(); //update PID control value, and set to motors 44 | float Roll(); //get roll angle 45 | float Pitch(); //get pitch angle 46 | float Yaw(); //get yaw angle 47 | float TargetRoll(); //get target roll angle 48 | float TargetPitch(); //get target pitch angle 49 | float TargetYaw(); //get target yaw angle 50 | void SetRollPID(float Kp,float Ki, float Kd); //set pid parameters of roll 51 | void SetPitchPID(float Kp,float Ki, float Kd); //set pid parameters of pitch 52 | void SetYawPID(float Kp,float Ki, float Kd); //set pid parameters of yaw 53 | void Arm(); 54 | void DisArm(); 55 | }; 56 | 57 | 58 | 59 | #endif 60 | 61 | -------------------------------------------------------------------------------- /libraries/OffChip/HMI/HMI.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/HMI/HMI.cpp -------------------------------------------------------------------------------- /libraries/OffChip/HMI/HMI.h: -------------------------------------------------------------------------------- 1 | /**@file HMI.h 2 | *@brief HMI串口屏驱动,使其更加方便的使用串口屏来显示数据 3 | * 使用: 4 | * 5 | * 6 | * 7 | * 8 | *@author lissettecarlr 9 | * 10 | */ 11 | 12 | #ifndef __HMI_H 13 | #define __HMI_H 14 | 15 | #include "stm32f10x.h" 16 | #include "USART.h" 17 | #include "TaskManager.h" 18 | #include "stdio.h" 19 | 20 | class HMI 21 | { 22 | private: 23 | USART &COM; 24 | 25 | 26 | public: 27 | 28 | HMI(USART &HMI_com); 29 | 30 | bool setTextBox(char *ControlsName,char *Content); 31 | bool setTextBox(char *ControlsName,float val,u8 decimals); 32 | bool setTextBox(char *ControlsName,int val); 33 | 34 | bool flushPage(char *Page); 35 | bool vis(char *ControlsName,bool state); //1显示 0隐藏 36 | // bool SetTextBox(char *name,char *txt);//设置文本框 37 | // bool SetProgressBar(char *name,char val);//设置进度条 38 | 39 | // bool SetTextBox(USART &com,char *name,char *txt);//设置文本框 40 | // bool SetProgressBar(USART &com,char *name,char *val);//设置进度条 41 | 42 | 43 | /**********************************Personal function**************************************/ 44 | bool outputDirection(char *ControlsName,u8 direction); //九宫格表示 45 | 46 | }; 47 | 48 | #endif 49 | 50 | /**********************************Personal define**************************************/ 51 | #define UI_PITCH "t6" 52 | #define UI_ROOL "t7" 53 | #define UI_YAW "t8" 54 | #define UI_THR "t9" 55 | #define UI_RcPower "t21" 56 | #define UI_CopterPower "t22" 57 | #define UI_DirectionL "t19" 58 | #define UI_DirectionR "t20" 59 | #define UI_CoefficientL "t14" 60 | #define UI_CoefficientR "t15" 61 | #define UI_Hight "t11" 62 | #define UI_AliveTime "t13" 63 | #define UI_FlyClock "p0" 64 | 65 | 66 | -------------------------------------------------------------------------------- /libraries/OffChip/InertialSensor/InertialSensor.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/InertialSensor/InertialSensor.cpp -------------------------------------------------------------------------------- /libraries/OffChip/InertialSensor/InertialSensor.h: -------------------------------------------------------------------------------- 1 | #ifndef _INERTIAL_SENSOR_H_ 2 | #define _INERTIAL_SENSOR_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "Mathtool.h" 6 | #include "Sensor.h" 7 | 8 | class InertialSensor : public Sensor 9 | { 10 | protected: 11 | Vector3 _acc_offset; //acc offset 12 | Vector3 _gyro_offset; //gyro offset 13 | Vector3 _acc_raw; 14 | Vector3 _gyro_raw; 15 | Vector3f _acc_g; 16 | Vector3f _gyro_rad; 17 | 18 | 19 | bool _gyro_calibrating; 20 | Vector3 _gyro_calibrate_sum; //sum of gyro for average aclibrate 21 | u16 _gyro_calibrate_cnt; //count of sum gyro data 22 | 23 | 24 | public: 25 | virtual bool Initialize(void) = 0; 26 | virtual bool Update(Vector3f &acc, Vector3f &gyro)=0; 27 | s16 AccRawX() { return _acc_raw.x; } 28 | s16 AccRawY() { return _acc_raw.y; } 29 | s16 AccRawZ() { return _acc_raw.z; } 30 | s16 GyroRawX() { return _gyro_raw.x; } 31 | s16 GyroRawY() { return _gyro_raw.y; } 32 | s16 GyroRawZ() { return _gyro_raw.z; } 33 | Vector3 AccRaw() { return _acc_raw;} 34 | Vector3 GyroRaw() { return _gyro_raw;} 35 | float AccX() { return _acc_g.x; } 36 | float AccY() { return _acc_g.y; } 37 | float AccZ() { return _acc_g.z; } 38 | float GyroX() { return _gyro_rad.x; } 39 | float GyroY() { return _gyro_rad.y; } 40 | float GyroZ() { return _gyro_rad.z; } 41 | Vector3f Acc() { return _acc_g; } 42 | Vector3f Gyro() { return _gyro_rad; } 43 | 44 | Vector3 AccOffset() { return _acc_offset;} 45 | Vector3 GyroOffset() { return _gyro_offset;} 46 | void SetAccOffset(Vector3 accOff) { _acc_offset = accOff; } 47 | void SetGyroOffset(Vector3 gyroOff) { _gyro_offset = gyroOff;} 48 | void StartGyroCalibrating() 49 | { 50 | _gyro_calibrating = true; 51 | _gyro_calibrate_cnt = 0; 52 | _gyro_calibrate_sum.Zero(); 53 | } 54 | void StopGyroCalibrating() { _gyro_calibrating = false;} 55 | bool GyroCalibrating() { return _gyro_calibrating; } 56 | bool Ready() { return !GyroCalibrating(); } 57 | }; 58 | 59 | 60 | #endif 61 | 62 | -------------------------------------------------------------------------------- /libraries/OffChip/InertialSensor/MPU6050.h: -------------------------------------------------------------------------------- 1 | #ifndef _MPU6050_H_ 2 | #define _MPU6050_H_ 3 | #include "stm32f10x.h" 4 | #include "I2C.h" 5 | #include "MathTool.h" 6 | #include "InertialSensor.h" 7 | 8 | //MPU6050 IIC Address 9 | #define MPU6050_ADDRESS_AD0_LOW 0x68 //address pin low (GND) 10 | #define MPU6050_ADDRESS_AD0_HIGH 0x69 //address pin high (VCC) 11 | #define MPU6050_DEFAULT_ADDRESS 0xD0 //MPU6050_ADDRESS_AD0_LOW ((MPU6050_ADDRESS_AD0_LOW<<1)&0xFE) or ((MPU6050_ADDRESS_AD0_HIGH<<1)&0xFE) 12 | #define MPU6050_ADDRESS MPU6050_DEFAULT_ADDRESS 13 | 14 | //MPU6050 Register Address 15 | #define SMPLRT_DIV 0x19 //sample rate of gyro. typically: 0x07(125Hz) 16 | #define CONFIG 0x1A //low pass filter, typically: 0x06(5Hz) 17 | #define GYRO_CONFIG 0x1B //gyro range and self test set, typically: 0x18(no selftest,2000deg/s) 18 | #define ACCEL_CONFIG 0x1C //acc range, self test, high pass filter. typically: 0x01(no self test,2G,5Hz) 19 | #define ACCEL_XOUT_H 0x3B //acc x hight byte, register address 20 | #define ACCEL_XOUT_L 0x3C //acc x low byte, register address 21 | #define ACCEL_YOUT_H 0x3D //acc y hight byte, register address 22 | #define ACCEL_YOUT_L 0x3E //acc y low byte, register address 23 | #define ACCEL_ZOUT_H 0x3F //acc z hight byte, register address 24 | #define ACCEL_ZOUT_L 0x40 //acc z low byte, register address 25 | #define TEMP_OUT_H 0x41 //temperature hight byte, register address 26 | #define TEMP_OUT_L 0x42 //temperature low byte, register address 27 | #define GYRO_XOUT_H 0x43 //gyro x hight byte, register address 28 | #define GYRO_XOUT_L 0x44 //gyro x low byte, register address 29 | #define GYRO_YOUT_H 0x45 //gyro y hight byte, register address 30 | #define GYRO_YOUT_L 0x46 //gyro y low byte, register address 31 | #define GYRO_ZOUT_H 0x47 //gyro z hight byte, register address 32 | #define GYRO_ZOUT_L 0x48 //gyro z low byte, register address 33 | #define PWR_MGMT_1 0x6B //power management, typically: 0x00(work normally) 34 | #define WHO_AM_I 0x75 //self identify, typically: (0x68, read only) 35 | #define I2C_MST_CTRL 0x24 36 | #define I2C_SLV0_ADDR 0x25 //slave0 device address 37 | #define I2C_SLV0_REG 0x26 //slave0 register address 38 | #define I2C_SLV0_CTRL 0x27 // 39 | #define I2C_SLV0_DO 0x63 //data write to slave0 40 | #define USER_CTRL 0x6A //enable settings: FIFO, I2C master mode, I2C interface 41 | #define INT_PIN_CFG 0x37 42 | #define EXT_SENS_DATA_00 0x49 43 | #define EXT_SENS_DATA_01 0x4A 44 | #define EXT_SENS_DATA_02 0x4B 45 | #define EXT_SENS_DATA_03 0x4C 46 | #define EXT_SENS_DATA_04 0x4D 47 | #define EXT_SENS_DATA_05 0x4E 48 | #define EXT_SENS_DATA_06 0x4F 49 | #define EXT_SENS_DATA_07 0x50 50 | #define EXT_SENS_DATA_08 0x51 51 | #define EXT_SENS_DATA_09 0x52 52 | #define EXT_SENS_DATA_10 0x53 53 | #define EXT_SENS_DATA_11 0x54 54 | 55 | #define AVG_FILTER_LEN 5 //the length of average filter 56 | 57 | 58 | class MPU6050:public InertialSensor 59 | { 60 | protected: 61 | I2C &_i2c; //i2c bus device 62 | Vector3f _acc_filter[AVG_FILTER_LEN]; //sum of acc data 63 | Vector3f _gyro_filter[AVG_FILTER_LEN]; //sum of gyro data 64 | u16 _filter_idx; //arry index for acc/gyro filter 65 | u8 _raw_data[15]; //raw data of MPU6050 66 | bool _health; 67 | 68 | 69 | public: 70 | MPU6050(I2C &i2c); 71 | bool getHealth(); 72 | virtual bool Initialize(void); 73 | virtual bool Update(Vector3f &acc, Vector3f &gyro); 74 | }; 75 | 76 | 77 | #endif 78 | 79 | 80 | 81 | -------------------------------------------------------------------------------- /libraries/OffChip/Joystick/Joystick.cpp: -------------------------------------------------------------------------------- 1 | #include "Joystick.h" 2 | 3 | 4 | 5 | Joystick::Joystick(ADC &adc,u8 LX,u8 LY,u8 NX,u8 NY):mAdc(adc) 6 | { 7 | mCH_LX=LX; 8 | mCH_LY=LY; 9 | mCH_NX=NX; 10 | mCH_NY=NY; 11 | } 12 | 13 | 14 | bool Joystick::Updata() 15 | { 16 | 17 | mLX_Val=mAdc[mCH_LX]; 18 | mLY_Val=mAdc[mCH_LY]; 19 | mNX_Val=mAdc[mCH_NX]; 20 | mNY_Val=mAdc[mCH_NY]; 21 | 22 | return true; 23 | 24 | } 25 | 26 | 27 | u8 Joystick::getLeftState() //左上向右数的九宫格 28 | { 29 | u8 Xtemp,Ytemp; 30 | 31 | //左右判断 32 | if(mLX_Val ==0) 33 | return 0; 34 | else if(mLX_ValLX_LEFT_THRESHOLDS) //向左搬动了 37 | Xtemp=4; 38 | else 39 | Xtemp=5; 40 | 41 | //上下判断 42 | if(mLY_Val ==0) 43 | return 0; 44 | else if(mLY_Val>LX_UP_THRESHOLDS)//向上搬动了 45 | Ytemp=2; 46 | else if(mLY_ValNX_NIGHT_THRESHOLDS) //向右搬动了 86 | Xtemp=6; 87 | else if(mNX_ValNX_DOWN_THRESHOLDS)//向下搬动了 98 | Ytemp=8; 99 | else 100 | Ytemp=5; 101 | 102 | //综合返回 103 | if(Xtemp==4 && Ytemp==2) //左上 104 | return 1; 105 | if(Xtemp==5 && Ytemp==2) //上 106 | return 2; 107 | if(Xtemp==6 && Ytemp==2) //右上 108 | return 3; 109 | if(Xtemp==4 && Ytemp==5) //左 110 | return 4; 111 | if(Xtemp==5 && Ytemp==5) //中 112 | return 5; 113 | if(Xtemp==6 && Ytemp==5) //右 114 | return 6; 115 | if(Xtemp==4 && Ytemp==8) //左下 116 | return 7; 117 | if(Xtemp==5 && Ytemp==8) //下 118 | return 8; 119 | if(Xtemp==6 && Ytemp==8) //右下 120 | return 9; 121 | 122 | return 0;//错误退出 123 | } 124 | -------------------------------------------------------------------------------- /libraries/OffChip/Joystick/Joystick.h: -------------------------------------------------------------------------------- 1 | #ifndef _JOYSTICK_H 2 | #define _JOYSTICK_H 3 | 4 | #include "stm32f10x.h" 5 | #include "ADC.h" 6 | 7 | 8 | 9 | 10 | //左摇杆X 在小于2的时候判定为向右搬动了,在大于3的时候判定为左搬动 11 | //左摇杆Y 在大于1的时候判定为向上搬动了, 在小于0.5的时候判定为向下搬动了 12 | 13 | //右摇杆X 在小于0.7的时候判定为向左搬动了,在大于1的时候判定为向右搬动了 14 | //右摇杆Y 在小于2的时候判定为向上搬动了,在大于3的时候判定为向下搬动了 15 | #define LX_NIGHT_THRESHOLDS 2 16 | #define LX_LEFT_THRESHOLDS 3 17 | #define LX_UP_THRESHOLDS 1 18 | #define LX_DOWN_THRESHOLDS 0.5 19 | 20 | 21 | #define NX_NIGHT_THRESHOLDS 1 22 | #define NX_LEFT_THRESHOLDS 0.7 23 | #define NX_UP_THRESHOLDS 2 24 | #define NX_DOWN_THRESHOLDS 3 25 | 26 | 27 | class Joystick{ 28 | 29 | private: 30 | ADC &mAdc; 31 | u8 mCH_LX,mCH_LY,mCH_NX,mCH_NY; 32 | float mLX_Val; 33 | float mLY_Val; 34 | float mNX_Val; 35 | float mNY_Val; 36 | 37 | public: 38 | Joystick(ADC &adc,u8 LX,u8 LY,u8 NX,u8 NY); 39 | bool Updata(); 40 | u8 getLeftState(); //左上向右数的九宫格 41 | u8 getNightState(); 42 | 43 | }; 44 | 45 | 46 | #endif 47 | 48 | 49 | //X1(5): 中间值:2.56 最小:(右移)0.008 最大(左移) 3.299 50 | //Y1(6): 0.87 (下移)0.005 (上移) 2.98 51 | //X2(8): 0.83 (左移)0.002 (右移) 2.89 52 | //Y2(9): 2.27 (上移)0.010 (下移) 3.299 53 | 54 | //左摇杆X 在小于2的时候判定为向右搬动了,在大于3的时候判定为左搬动 55 | //左摇杆Y 在大于1的时候判定为向上搬动了, 在小于0.5的时候判定为向下搬动了 56 | 57 | //右摇杆X 在小于0.7的时候判定为向左搬动了,在大于1的时候判定为向右搬动了 58 | //右摇杆Y 在小于2的时候判定为向上搬动了,在大于3的时候判定为向下搬动了 59 | 60 | -------------------------------------------------------------------------------- /libraries/OffChip/LED/LED.cpp: -------------------------------------------------------------------------------- 1 | #include "LED.h" 2 | #include "TaskManager.h" 3 | 4 | const u16 LED::mPin[16]={GPIO_Pin_0, GPIO_Pin_1, GPIO_Pin_2, GPIO_Pin_3, 5 | GPIO_Pin_4, GPIO_Pin_5, GPIO_Pin_6, GPIO_Pin_7, 6 | GPIO_Pin_8, GPIO_Pin_9, GPIO_Pin_10, GPIO_Pin_11, 7 | GPIO_Pin_12, GPIO_Pin_13, GPIO_Pin_14, GPIO_Pin_15}; 8 | 9 | LED::LED(GPIO_TypeDef* GPIOx, u16 Pinx, bool lowOn) 10 | { 11 | mPort = GPIOx; 12 | mSelectPin = Pinx; 13 | mLowOn = lowOn; 14 | mLedOn = false; 15 | mNewTime = 0; 16 | mOldTime = 0; 17 | 18 | if(mPort==GPIOA) RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA,ENABLE); 19 | if(mPort==GPIOB) RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB,ENABLE); 20 | if(mPort==GPIOC) RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC,ENABLE); 21 | if(mPort==GPIOD) RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD,ENABLE); 22 | if(mPort==GPIOE) RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOE,ENABLE); 23 | if(mPort==GPIOF) RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF,ENABLE); 24 | 25 | GPIO_InitTypeDef GPIO_InitStructure; 26 | GPIO_InitStructure.GPIO_Pin = mPin[mSelectPin]; 27 | GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; 28 | GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; 29 | GPIO_Init(mPort,&GPIO_InitStructure); 30 | } 31 | 32 | 33 | void LED::On() 34 | { 35 | if(mLowOn) 36 | GPIO_ResetBits(mPort,mPin[mSelectPin]); 37 | else 38 | GPIO_SetBits(mPort,mPin[mSelectPin]); 39 | } 40 | 41 | void LED::Off() 42 | { 43 | if(mLowOn) 44 | GPIO_SetBits(mPort,mPin[mSelectPin]); 45 | else 46 | GPIO_ResetBits(mPort,mPin[mSelectPin]); 47 | } 48 | 49 | void LED::Hz(u16 frq) 50 | { 51 | mNewTime = tskmgr.Time(); 52 | if(mNewTime-mOldTime > 1.0/double(frq)) 53 | { 54 | mLedOn = !mLedOn; 55 | mOldTime = mNewTime; 56 | if(mLedOn) On(); 57 | else Off(); 58 | } 59 | } 60 | 61 | 62 | -------------------------------------------------------------------------------- /libraries/OffChip/LED/LED.h: -------------------------------------------------------------------------------- 1 | #ifndef _LED_H_ 2 | #define _LED_H_ 3 | 4 | #include "stm32f10x.h" 5 | 6 | class LED 7 | { 8 | private: 9 | static const u16 mPin[16]; //Pin0 ~ Pin15 10 | GPIO_TypeDef* mPort; //GPIOx 11 | u16 mSelectPin; //Pinx 12 | bool mLowOn; //true = led on when pin level low; false = led on when pin high 13 | bool mLedOn; //true = led on; false = led off 14 | double mNewTime; //new time 15 | double mOldTime; //old time 16 | public: 17 | LED(GPIO_TypeDef* GPIOx, u16 Pinx, bool lowOn=true); 18 | void On(); 19 | void Off(); 20 | void Hz(u16 frq); 21 | }; 22 | 23 | 24 | 25 | #endif 26 | 27 | 28 | -------------------------------------------------------------------------------- /libraries/OffChip/MHZ14/MHZ14.cpp: -------------------------------------------------------------------------------- 1 | #include "MHZ14.h" 2 | 3 | MHZ14::MHZ14(USART &com) 4 | :COM(com) 5 | { 6 | //一帧数据读取指令 7 | Command_getvalue[0]=0xff; 8 | Command_getvalue[1]=0x01; 9 | Command_getvalue[2]=0x86; 10 | Command_getvalue[3]=0; 11 | Command_getvalue[4]=0; 12 | Command_getvalue[5]=0; 13 | Command_getvalue[6]=0; 14 | Command_getvalue[7]=0; 15 | Command_getvalue[8]=0x79; 16 | 17 | DATA_H=0; 18 | DATA_L=0; 19 | } 20 | 21 | 22 | bool MHZ14::SumCheck(u8 data[9]) 23 | { 24 | u8 sum=0,check=0; 25 | for(u8 i=1;i<8;i++) 26 | { 27 | sum+=data[i]; 28 | } 29 | check=0xff-sum+0x01; 30 | if(data[8]==check) 31 | return true ; 32 | else 33 | return false; 34 | } 35 | 36 | u16 MHZ14::GetValue() 37 | { 38 | return CO2_Concentration; 39 | } 40 | 41 | 42 | bool MHZ14::Updata() 43 | { 44 | //向模块发送获取数据 45 | COM.SendData(Command_getvalue,9); 46 | 47 | //判断是否有数据返回 48 | if(COM.ReceiveBufferSize()<9) 49 | { 50 | COM.ClearReceiveBuffer(); //清空接收缓存 51 | return false; 52 | } 53 | else 54 | { 55 | COM.GetReceivedData(rev_buffer,9); //取出一帧数据 56 | COM.ClearReceiveBuffer(); //清空接收缓存 57 | 58 | if(SumCheck(rev_buffer)==false) //校验和 59 | return false; 60 | else 61 | { 62 | DATA_H=rev_buffer[2]; 63 | DATA_L=rev_buffer[3]; 64 | CO2_Concentration=rev_buffer[2]*256+rev_buffer[3]; //计算浓度 65 | return true; 66 | } 67 | } 68 | } 69 | 70 | -------------------------------------------------------------------------------- /libraries/OffChip/MHZ14/MHZ14.h: -------------------------------------------------------------------------------- 1 | /* 2 | 3 | */ 4 | 5 | 6 | 7 | #include "USART.h" 8 | #include "TaskManager.h" 9 | 10 | class MHZ14 { 11 | 12 | private: 13 | USART &COM; 14 | u8 Command_getvalue[9]; //发送命令 15 | u8 rev_buffer[9]; 16 | u16 CO2_Concentration; 17 | bool SumCheck(u8 data[9]); 18 | public: 19 | u8 DATA_H; 20 | u8 DATA_L; 21 | MHZ14(USART &com); 22 | bool Updata();//更新数据,返回是否更新成功 true false 23 | u16 GetValue(); //得到一个浓度数据 24 | 25 | }; 26 | -------------------------------------------------------------------------------- /libraries/OffChip/Monitor/Monitor.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/Monitor/Monitor.cpp -------------------------------------------------------------------------------- /libraries/OffChip/Monitor/Monitor.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/Monitor/Monitor.h -------------------------------------------------------------------------------- /libraries/OffChip/Motor/StepMotor.cpp: -------------------------------------------------------------------------------- 1 | #include "StepMotor.h" 2 | #include "USART.h" 3 | 4 | extern USART com; 5 | 6 | bool StepMotor::bInitSPWM = false; 7 | float StepMotor::SPWM[256] = {0}; 8 | 9 | 10 | void StepMotor::InitSPWM() 11 | { 12 | for(int i=0;i<256;i++) 13 | { 14 | SPWM[i] = sin(i*2.0*3.1415926/256.0); 15 | } 16 | } 17 | 18 | StepMotor::StepMotor(PWM *pwma, u8 cha, PWM *pwmb, u8 chb, PWM *pwmc, u8 chc, float power) 19 | { 20 | _pwm_a = pwma; 21 | _pwm_b = pwmb; 22 | _pwm_c = pwmc; 23 | _ch_a = cha; 24 | _ch_b = chb; 25 | _ch_c = chc; 26 | _maxPower = power; 27 | _armed = false; 28 | if(bInitSPWM) return; 29 | bInitSPWM = true; 30 | InitSPWM(); 31 | } 32 | 33 | void StepMotor::Initialize(PWM *pwma, u8 cha, PWM *pwmb, u8 chb, PWM *pwmc, u8 chc, float power) 34 | { 35 | _pwm_a = pwma; 36 | _pwm_b = pwmb; 37 | _pwm_c = pwmc; 38 | _ch_a = cha; 39 | _ch_b = chb; 40 | _ch_c = chc; 41 | _maxPower = power; 42 | 43 | } 44 | 45 | 46 | void StepMotor::SetPosition(int position) 47 | { 48 | if(!_armed) return; 49 | float a,b,c; 50 | 51 | u16 pos = position & 0xFF; 52 | 53 | a = SPWM[pos%256]; 54 | b = SPWM[(pos+85)%256]; 55 | c = SPWM[(pos+170)%256]; 56 | 57 | a = (_maxPower*a + 1.0)/2.0; 58 | b = (_maxPower*b + 1.0)/2.0; 59 | c = (_maxPower*c + 1.0)/2.0; 60 | 61 | _pwm_a->SetDuty(_ch_a,a*100); 62 | _pwm_b->SetDuty(_ch_b,b*100); 63 | _pwm_c->SetDuty(_ch_c,c*100); 64 | } 65 | void StepMotor::Enable() 66 | { 67 | _armed = true; 68 | } 69 | void StepMotor::Disable() 70 | { 71 | _armed = false; 72 | _pwm_a->SetDuty(_ch_a,0); 73 | _pwm_b->SetDuty(_ch_b,0); 74 | _pwm_c->SetDuty(_ch_c,0); 75 | } 76 | 77 | 78 | -------------------------------------------------------------------------------- /libraries/OffChip/Motor/StepMotor.h: -------------------------------------------------------------------------------- 1 | #ifndef _STEP_MOTOR_H_ 2 | #define _STEP_MOTOR_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "math.h" 6 | #include "PWM.h" 7 | 8 | class StepMotor 9 | { 10 | private: 11 | static bool bInitSPWM; 12 | static float SPWM[256]; 13 | PWM *_pwm_a; 14 | PWM *_pwm_b; 15 | PWM *_pwm_c; 16 | u8 _ch_a; 17 | u8 _ch_b; 18 | u8 _ch_c; 19 | float _maxPower; 20 | bool _armed; 21 | private: 22 | static void InitSPWM(); 23 | public: 24 | StepMotor(PWM *pwma, u8 cha, PWM *pwmb, u8 chb, PWM *pwmc, u8 chc, float power); 25 | void Initialize(PWM *pwma, u8 cha, PWM *pwmb, u8 chb, PWM *pwmc, u8 chc, float power); 26 | void SetPosition(int pos); 27 | void Enable(); 28 | void Disable(); 29 | }; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/Remade.md: -------------------------------------------------------------------------------- 1 | # 问题 # 2 | NRF24L01暂时无法使用SPI中断接收数据; -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/demo/RTE/RTE_Components.h: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | * Auto generated Run-Time-Environment Component Configuration File 4 | * *** Do not modify ! *** 5 | * 6 | * Project: 'NRF24L01' 7 | * Target: 'Target 1' 8 | */ 9 | 10 | #ifndef RTE_COMPONENTS_H 11 | #define RTE_COMPONENTS_H 12 | 13 | #define RTE_DEVICE_STDPERIPH_DMA 14 | #define RTE_DEVICE_STDPERIPH_EXTI 15 | #define RTE_DEVICE_STDPERIPH_FRAMEWORK 16 | #define RTE_DEVICE_STDPERIPH_GPIO 17 | #define RTE_DEVICE_STDPERIPH_RCC 18 | #define RTE_DEVICE_STDPERIPH_SPI 19 | #define RTE_DEVICE_STDPERIPH_TIM 20 | #define RTE_DEVICE_STDPERIPH_USART 21 | 22 | #endif /* RTE_COMPONENTS_H */ 23 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/demo/main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/demo/main.cpp -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/lib/NRF24L01.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/lib/NRF24L01.cpp -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/lib/NRF24L01.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/lib/NRF24L01.h -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/IMU/CRC.cpp: -------------------------------------------------------------------------------- 1 | #include "CRC.h" 2 | uint16_t CRC16Calculate(const uint8_t *data, uint16_t size) 3 | { 4 | uint16_t out = 0; 5 | int bits_read = 0, bit_flag; 6 | 7 | /* Sanity check: */ 8 | if(data == 0) 9 | return 0; 10 | 11 | while(size > 0) 12 | { 13 | bit_flag = out >> 15; 14 | 15 | /* Get next bit: */ 16 | out <<= 1; 17 | out |= (*data >> bits_read) & 1; // item a) work from the least significant bits 18 | 19 | /* Increment bit counter: */ 20 | bits_read++; 21 | if(bits_read > 7) 22 | { 23 | bits_read = 0; 24 | data++; 25 | size--; 26 | } 27 | 28 | /* Cycle check: */ 29 | if(bit_flag) 30 | out ^= CRC16; 31 | 32 | } 33 | 34 | // item b) "push out" the last 16 bits 35 | int i; 36 | for (i = 0; i < 16; ++i) { 37 | bit_flag = out >> 15; 38 | out <<= 1; 39 | if(bit_flag) 40 | out ^= CRC16; 41 | } 42 | 43 | // item c) reverse the bits 44 | uint16_t crc = 0; 45 | i = 0x8000; 46 | int j = 0x0001; 47 | for (; i != 0; i >>=1, j <<= 1) { 48 | if (i & out) crc |= j; 49 | } 50 | 51 | return crc; 52 | } 53 | 54 | 55 | 56 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/IMU/CRC.h: -------------------------------------------------------------------------------- 1 | # ifndef __CRC_H 2 | # define __CRC_H 3 | 4 | 5 | #include 6 | 7 | 8 | #define CRC16 0x8005 9 | 10 | uint16_t CRC16Calculate(const uint8_t *data, uint16_t size); 11 | 12 | #endif 13 | 14 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/IMU/Matrix3.h: -------------------------------------------------------------------------------- 1 | #ifndef _MATRIX3_H_ 2 | #define _MATRIX3_H_ 3 | #include "Quaternion.h" 4 | #include "Vector3.h" 5 | 6 | template 7 | class Matrix3 8 | { 9 | public: 10 | Vector3 a; //the 1st row 11 | Vector3 b; //the 2nd row 12 | Vector3 c; //the 3rd row 13 | public: 14 | Matrix3() { } //zero the vector elements 15 | Matrix3(const Vector3 &a0, const Vector3 &b0, const Vector3 &c0) : a(a0), b(b0), c(c0) {} 16 | Matrix3(const T ax, const T ay, const T az, const T bx, const T by, const T bz, const T cx, const T cy, const T cz) : a(ax,ay,az), b(bx,by,bz), c(cx,cy,cz) { } 17 | void operator() (const Vector3 &a0, const Vector3 &b0, const Vector3 &c0) {a = a0; b = b0; c = c0; } 18 | void operator() (const T ax, const T ay, const T az, const T bx, const T by, const T bz, const T cx, const T cy, const T cz) {a(ax,ay,az), b(bx,by,bz), c(cx,cy,cz); } 19 | bool operator==(const Matrix3 &m) { return (a==m.a && b==m.b && c==m.c); } 20 | bool operator!= (const Matrix3 &m){ return (a!=m.a || b!=m.b || c!=m.c); } 21 | Matrix3 operator-(void) const { return Matrix3(-a,-b,-c); } 22 | Matrix3 operator-(const Matrix3 &m) const { return Matrix3(a-m.a, b-m.b, c-m.c); } 23 | Matrix3 operator+(const Matrix3 &m) const { return Matrix3(a+m.a, b+m.b, c+m.c); } 24 | Matrix3 operator*(const T num) const { return Matrix3(a*num, b*num, c*num); } 25 | Matrix3 operator/(const T num) const { return Matrix3(a/num, b/num, c/num); } 26 | Matrix3 &operator+= (const Matrix3 &m) { return *this = *this + m; } 27 | Matrix3 &operator-= (const Matrix3 &m) { return *this = *this - m; } 28 | Matrix3 &operator*= (const T num) { return *this = *this * num; } 29 | Matrix3 &operator/= (const T num) { return *this = *this / num; } 30 | Vector3 operator *(const Vector3 &v) const { return Vector3(a.x*v.x+a.y*v.y+a.z*v.z, b.x*v.x+b.y*v.y+b.z*v.z, c.x*v.x+c.y*v.y+c.z*v.z); } 31 | Matrix3 operator *(const Matrix3 &m) const 32 | { 33 | Matrix3 temp (Vector3(a.x*m.a.x+a.y*m.b.x+a.z*m.c.x, a.x*m.a.y+a.y*m.b.y+a.z*m.c.y, a.x*m.a.z+a.y*m.b.z+a.z*m.c.z), 34 | Vector3(b.x*m.a.x+b.y*m.b.x+b.z*m.c.x, b.x*m.a.y+b.y*m.b.y+b.z*m.c.y, b.x*m.a.z+b.y*m.b.z+b.z*m.c.z), 35 | Vector3(c.x*m.a.x+c.y*m.b.x+c.z*m.c.x, c.x*m.a.y+c.y*m.b.y+c.z*m.c.y, c.x*m.a.z+c.y*m.b.z+c.z*m.c.z)); 36 | return temp; 37 | } 38 | void Zero(void) { a.x = a.y = a.z = 0; b.x = b.y = b.z = 0; c.x = c.y = c.z = 0; } 39 | void Identity(void) { a.x = b.y = c.z = 1; a.y = a.z = 0; b.x = b.z = 0; c.x = c.y = 0; } 40 | bool IsNan(void) { return a.IsNan() || b.IsNan() || c.IsNan(); } 41 | void Normalize(void) 42 | { 43 | float error = a * b; 44 | Vector3 t0 = a - (b * (0.5f * error)); 45 | Vector3 t1 = b - (a * (0.5f * error)); 46 | Vector3 t2 = t0 % t1; 47 | a = t0 * (1.0f / t0.Length()); 48 | b = t1 * (1.0f / t1.Length()); 49 | c = t2 * (1.0f / t2.Length()); 50 | } 51 | void Rotate(const Vector3 &g) 52 | { 53 | Matrix3 temp_matrix; 54 | temp_matrix.a.x = a.y * g.z - a.z * g.y; 55 | temp_matrix.a.y = a.z * g.x - a.x * g.z; 56 | temp_matrix.a.z = a.x * g.y - a.y * g.x; 57 | temp_matrix.b.x = b.y * g.z - b.z * g.y; 58 | temp_matrix.b.y = b.z * g.x - b.x * g.z; 59 | temp_matrix.b.z = b.x * g.y - b.y * g.x; 60 | temp_matrix.c.x = c.y * g.z - c.z * g.y; 61 | temp_matrix.c.y = c.z * g.x - c.x * g.z; 62 | temp_matrix.c.z = c.x * g.y - c.y * g.x; 63 | (*this) += temp_matrix; 64 | } 65 | Matrix3 Transpose(void) const{ return Matrix3(Vector3(a.x,b.x,c.x), Vector3(a.y,b.y,c.y), Vector3(a.z,b.z,c.z)); } 66 | Vector3f ToEuler() const 67 | { 68 | Vector3f angle; 69 | angle.x = -asinf(c.x); 70 | angle.y = atan2f(c.y, c.z); 71 | angle.z = atan2f(b.x, a.x); 72 | 73 | return angle; 74 | } 75 | }; 76 | 77 | 78 | #endif 79 | 80 | 81 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/IMU/Quaternion.h: -------------------------------------------------------------------------------- 1 | #ifndef _QUATERNION_H_ 2 | #define _QUATERNION_H_ 3 | 4 | #include "math.h" 5 | 6 | class Quaternion 7 | { 8 | public: 9 | float q1, q2, q3, q4; 10 | public: 11 | // constructor creates a quaternion equivalent to roll=0, pitch=0, yaw=0 12 | Quaternion() { q1 = 1; q2 = q3 = q4 = 0; } 13 | // setting constructor 14 | Quaternion(float _q1, float _q2, float _q3, float _q4):q1(_q1), q2(_q2), q3(_q3), q4(_q4) {} 15 | // function call operator 16 | void operator()(float _q1, float _q2, float _q3, float _q4) {q1 = _q1; q2 = _q2; q3 = _q3; q4 = _q4; } 17 | // check if any elements are NAN 18 | bool IsNan(void) { return isnan(q1) || isnan(q2) || isnan(q3) || isnan(q4); } 19 | // create eulers from a quaternion 20 | void ToEuler(float &roll, float &pitch, float &yaw) 21 | { 22 | roll = atan2(2.0*(q1*q2 + q3*q4), 1 - 2.0*(q2*q2 + q3*q3)); 23 | pitch = asin(2.0*(q1*q3 - q4*q2)); 24 | yaw = atan2(2.0*(q1*q4 + q2*q3), 1 - 2.0*(q3*q3 + q4*q4)); 25 | } 26 | }; 27 | #endif // QUATERNION_H 28 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/IMU/Vector3.h: -------------------------------------------------------------------------------- 1 | #ifndef _VECTOR3_H_ 2 | #define _VECTOR3_H_ 3 | 4 | #include "math.h" 5 | 6 | template 7 | class Vector3 8 | { 9 | public: 10 | T x,y,z; 11 | public: 12 | //defualt constructor 13 | Vector3() { x = 0; y = 0; z = 0; } 14 | // setting ctor 15 | Vector3(T x0, T y0, T z0) : x(x0), y(y0), z(z0) {} 16 | //"()" overload 17 | void operator()(T x0, T y0, T z0){x= x0; y= y0; z= z0;} 18 | //"==" overload 19 | bool operator==(const Vector3 &v){return (x==v.x && y==v.y && z==v.z); } 20 | //"!=" overload 21 | bool operator!=(const Vector3 &v){return (x!=v.x || y!=v.y || z!=v.z); } 22 | // "-" negation overload 23 | Vector3 operator-(void) const { return Vector3(-x,-y,-z);} 24 | //"+" addition overload 25 | Vector3 operator+(const Vector3 &v) const { return Vector3(x+v.x, y+v.y, z+v.z); } 26 | //"-" subtraction overload 27 | Vector3 operator-(const Vector3 &v) const { return Vector3(x-v.x, y-v.y, z-v.z); } 28 | //"*" multiply overload 29 | Vector3 operator*(const T n)const { return Vector3(x*n, y*n, z*n); } 30 | //"/" divsion overload 31 | Vector3 operator/(const T n)const { return Vector3(x/n, y/n, z/n); } 32 | //"=" 33 | Vector3 &operator=(const Vector3 &v){x=v.x; y=v.y; z=v.z; return *this;} 34 | //"+=" overload 35 | Vector3 &operator+=(const Vector3 &v) { x+=v.x; y+=v.y; z+=v.z; return *this; } 36 | //"-=" overload 37 | Vector3 &operator-=(const Vector3 &v) { x-=v.x; y-=v.y; z-=v.z; return *this; } 38 | //"*=" overload 39 | Vector3 &operator*=(const T n) { x*=n; y*=n; z*=n; return *this; } 40 | // uniform scaling 41 | Vector3 &operator/=(const T n) { x/=n; y/=n; z/=n; return *this; } 42 | //dot product 43 | T operator*(const Vector3 &v) const { return x*v.x + y*v.y + z*v.z; } 44 | //cross product 45 | Vector3 operator %(const Vector3 &v)const { return Vector3(y*v.z-z*v.y, z*v.x-x*v.z, x*v.y-y*v.x);} 46 | // gets the length of this vector squared 47 | T LengthSquared() const { return (T)(*this * *this); } 48 | // gets the length of this vector 49 | float Length(void) const { return (T)sqrt(*this * *this); } 50 | // normalizes this vector 51 | void Normalize() { *this/=Length(); } 52 | // zero the vector 53 | void Zero() { x = y = z = 0.0; } 54 | // returns the normalized version of this vector 55 | Vector3 Normalized() const { return *this/Length(); } 56 | // check if any elements are NAN 57 | bool IsNan(void) { return isnan(x) || isnan(y) || isnan(z); } 58 | // check if any elements are infinity 59 | bool IsInf(void) { return isinf(x) || isinf(y) || isinf(z); } 60 | 61 | }; 62 | typedef Vector3 Vector3f; 63 | #endif // VECTOR3_H 64 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/IMU/attitude.h: -------------------------------------------------------------------------------- 1 | #ifndef __ATTITUDE_H_ 2 | #define __ATTITUDE_H_ 3 | 4 | #include "Vector3.h" 5 | #include "Matrix3.h" 6 | 7 | #define RtA 57.324841f //角度转化为弧度 8 | #define AtR 0.0174533f //弧度转化为角度 9 | 10 | class AttitudeCalculation{ 11 | 12 | private: 13 | 14 | Vector3f mAngle; 15 | Matrix3 mRotateMatrix; 16 | float q0, q1, q2 , q3 ; /** quaternion of sensor frame relative to auxiliary frame */ 17 | float dq0, dq1, dq2 , dq3; /** quaternion of sensor frame relative to auxiliary frame */ 18 | float gyro_bias[3]; /** bias estimation */ 19 | float q0q0, q0q1, q0q2, q0q3; 20 | float q1q1, q1q2, q1q3; 21 | float q2q2, q2q3; 22 | float q3q3; 23 | unsigned char bFilterInit; 24 | 25 | public: 26 | AttitudeCalculation() 27 | { 28 | q0 = 1.0f; 29 | } 30 | 31 | void NonlinearSO3AHRSinit(float ax, float ay, float az, float mx, float my, float mz); 32 | void NonlinearSO3AHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) ; 33 | Vector3f GetAngle(Vector3 acc, Vector3 gyro,float deltaT); 34 | Vector3f GetAngle(Vector3 acc, Vector3 gyro,Vector3 mag,float deltaT); 35 | 36 | }; 37 | 38 | 39 | 40 | 41 | #endif 42 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/Communication.h: -------------------------------------------------------------------------------- 1 | #ifndef _COMMUNICATION_H_ 2 | #define _COMMUNICATION_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "USART.h" 6 | #include "CRC.h" 7 | #include "Vector3.h" 8 | #include "NRF24L01.h" 9 | 10 | 11 | #define BYTE0(dwTemp) ( *( (char *)(&dwTemp) ) ) 12 | #define BYTE1(dwTemp) ( *( (char *)(&dwTemp) + 1) ) 13 | #define BYTE2(dwTemp) ( *( (char *)(&dwTemp) + 2) ) 14 | #define BYTE3(dwTemp) ( *( (char *)(&dwTemp) + 3) ) 15 | 16 | 17 | class Communication{ 18 | 19 | private: 20 | NRF24L01 &nrf; 21 | bool Calibration(u8 *data, int lenth, u8 check); 22 | 23 | public: 24 | 25 | //接收 26 | u16 mRcvTargetYaw; 27 | u16 mRcvTargetRoll; 28 | u16 mRcvTargetPitch; 29 | u16 mRcvTargetThr; 30 | u16 mRcvTargetHight; 31 | 32 | bool mClockState; //1为锁定,0为解锁 33 | 34 | bool mAcc_Calibrate; 35 | bool mGyro_Calibrate; 36 | bool mMag_Calibrate; 37 | 38 | bool mPidUpdata; //为true时表示有新的PID发来需要更新PID 39 | bool mGetPid; //为true时表示上位机需要获取当前PID的值 40 | 41 | Communication(NRF24L01 &nrf); 42 | bool DataListening();//数据接收监听 43 | 44 | float PID[9]; //暂存接收到的PID值 45 | 46 | // //上锁与解锁 47 | // bool FlightLockControl(bool flag); 48 | 49 | 50 | //发送 51 | //状态数据 52 | bool SendCopterState(float angle_rol, float angle_pit, float angle_yaw, s32 Hight, u8 fly_model, u8 armed); 53 | //传感器原始数据 54 | bool SendSensorOriginalData(Vector3 acc, Vector3 gyro, Vector3 mag); 55 | //接收到的控制量 56 | bool SendRcvControlQuantity(); 57 | //发送PID数据 58 | bool SendPID(float p1_p, float p1_i, float p1_d, float p2_p, float p2_i, float p2_d, float p3_p, float p3_i, float p3_d); 59 | //接收应答 需要应答的功能字和校验和 60 | bool reply(u8 difference, u8 sum); 61 | //发送电机信息 62 | void SendMotoMsg(u16 m_1, u16 m_2, u16 m_3, u16 m_4, u16 m_5, u16 m_6, u16 m_7, u16 m_8); 63 | //test 使用原始数据的通信方式来发送测试信息 64 | void test(float a, float b, float c, float d, float e, float f, float g, float h, float i); 65 | 66 | }; 67 | 68 | 69 | 70 | #endif 71 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/Control.h: -------------------------------------------------------------------------------- 1 | #ifndef __CONTROL_H_ 2 | #define __CONTROL_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "flash.h" 6 | #include "Vector3.h" 7 | #include "TaskManager.h" 8 | #include "F103_PWM.h" 9 | #include "math.h" 10 | 11 | 12 | //#define DUBUG_PITCH 13 | //#define DUBUG_ROLL 14 | #define NORMAL 15 | 16 | // PID结构体 17 | typedef struct 18 | { 19 | float P; 20 | float I; 21 | float D; 22 | float Desired; //期望 23 | float Error; //误差 24 | float LastError; //上一次的误差 25 | float CumulativeError;//积分累计误差 26 | float Proportion; //比例项 27 | float Integral;//积分项 28 | float Differential;//微分项 29 | float iLimit;//积分限制 30 | float Output;//最后输出 31 | float OLimit;//输出限幅 32 | 33 | }PID_Typedef; 34 | 35 | 36 | 37 | class Control{ 38 | private: 39 | 40 | PWM &mMoto; 41 | double TimeInterval; 42 | double OldTime; 43 | float FlyThr; //起飞油门量 经验值,用于区分使用PID的时间 44 | 45 | PID_Typedef pitch_angle_PID; //pitch角度环的PID 46 | PID_Typedef pitch_rate_PID; //pitch角速率环的PID 47 | 48 | PID_Typedef roll_angle_PID; //roll角度环的PID 49 | PID_Typedef roll_rate_PID; //roll角速率环的PID 50 | 51 | PID_Typedef yaw_angle_PID; //yaw角度环的PID 52 | PID_Typedef yaw_rate_PID; //yaw角速率环的PID 53 | 54 | //增量式PID工具 55 | //参数:需要更新的PID结构体,目标位置,当前位置,时间间隔 56 | bool TOOL_PID_Postion_Cal(PID_Typedef * PID, float target, float measure, float Thr, double dertT); 57 | public: 58 | Control(PWM &Moto); 59 | bool ReadPID(flash info, u16 Page, u16 position); 60 | bool SavePID(flash info, u16 Page, u16 position); 61 | 62 | //SET------------------------------------------------ 63 | bool SetPID_ROL(float P, float I, float D) 64 | { 65 | roll_angle_PID.P = P; 66 | roll_angle_PID.I = I; 67 | roll_angle_PID.D = D; 68 | return true; 69 | } 70 | 71 | bool SetPID_PIT(float P, float I, float D) 72 | { 73 | pitch_angle_PID.P = P; 74 | pitch_angle_PID.I = I; 75 | pitch_angle_PID.D = D; 76 | return true; 77 | } 78 | 79 | bool SetPID_YAW(float P, float I, float D) 80 | { 81 | yaw_angle_PID.P = P; 82 | yaw_angle_PID.I = I; 83 | yaw_angle_PID.D = D; 84 | return true; 85 | } 86 | //角速度环 87 | bool SetPID_ROL_rate(float P, float I, float D) 88 | { 89 | roll_rate_PID.P = P; 90 | roll_rate_PID.I = I; 91 | roll_rate_PID.D = D; 92 | return true; 93 | } 94 | 95 | bool SetPID_PIT_rate(float P, float I, float D) 96 | { 97 | pitch_rate_PID.P = P; 98 | pitch_rate_PID.I = I; 99 | pitch_rate_PID.D = D; 100 | return true; 101 | } 102 | 103 | bool SetPID_YAW_rate(float P, float I, float D) 104 | { 105 | yaw_rate_PID.P = P; 106 | yaw_rate_PID.I = I; 107 | yaw_rate_PID.D = D; 108 | return true; 109 | } 110 | 111 | //GET----------------------------------------------- 112 | PID_Typedef GetPID_ROL() 113 | { 114 | return roll_angle_PID; 115 | } 116 | 117 | PID_Typedef GetPID_YAW() 118 | { 119 | return yaw_angle_PID; 120 | } 121 | 122 | PID_Typedef GetPID_PIT() 123 | { 124 | return pitch_angle_PID; 125 | } 126 | 127 | PID_Typedef GetPID_ROL_rate() 128 | { 129 | return roll_rate_PID; 130 | } 131 | 132 | PID_Typedef GetPID_YAW_rate() 133 | { 134 | return yaw_rate_PID; 135 | } 136 | 137 | PID_Typedef GetPID_PIT_rate() 138 | { 139 | return pitch_rate_PID; 140 | } 141 | 142 | //传入: 当前角度/陀螺仪的角速度/遥控器量 143 | bool PIDControl(Vector3f angle, Vector3 gyr, u16 RcThr, u16 RcPit, u16 RcRol, u16 PcYaw); 144 | //串级PID 145 | bool SeriesPIDComtrol(Vector3f angle, Vector3 gyr, u16 RcThr, u16 RcPit, u16 RcRol, u16 PcYaw); 146 | 147 | 148 | }; 149 | 150 | 151 | #endif 152 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/Delay.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | *@file Delay.cpp 3 | *@author Neutree 4 | *@breif Delay Class 5 | *@copyright CQUT IOT Lib all rights reserved 6 | */ 7 | 8 | #include "Delay.h" 9 | 10 | 11 | 12 | void Delay::Ms(uint16_t nms) 13 | { 14 | u32 temp; 15 | if (nms == 0) 16 | return; 17 | SysTick->LOAD = 9000 * nms; 18 | SysTick->VAL = 0X00;//清空计数器 19 | SysTick->CTRL = 0X01;//使能,减到零是无动作,采用外部时钟源 20 | do 21 | { 22 | temp = SysTick->CTRL;//读取当前倒计数值 23 | } while ((temp & 0x01) && (!(temp&(1 << 16))));//等待时间到达 24 | SysTick->CTRL = 0x00; //关闭计数器 25 | SysTick->VAL = 0X00; //清空计数器 26 | } 27 | 28 | 29 | void Delay::Us(uint32_t nus) 30 | { 31 | u32 temp; 32 | if (nus == 0) 33 | return; 34 | SysTick->LOAD = 9 * nus; 35 | SysTick->VAL = 0X00;//清空计数器 36 | SysTick->CTRL = 0X01;//使能,减到零是无动作,采用外部时钟源 37 | do 38 | { 39 | temp = SysTick->CTRL;//读取当前倒计数值 40 | } while ((temp & 0x01) && (!(temp&(1 << 16))));//等待时间到达 41 | 42 | SysTick->CTRL = 0x00; //关闭计数器 43 | SysTick->VAL = 0X00; //清空计数器 44 | } 45 | 46 | 47 | 48 | void Delay::S(uint32_t ns) 49 | { 50 | u32 i; 51 | u32 temp; 52 | if (ns == 0) 53 | return; 54 | SysTick->LOAD = 9000000;//1S 55 | SysTick->VAL = 0X00;//清空计数器 56 | SysTick->CTRL = 0X01;//使能,减到零是无动作,采用外部时钟源 57 | for (i = 0; i < ns; ++i) 58 | { 59 | do 60 | { 61 | temp = SysTick->CTRL;//读取当前倒计数值 62 | } while ((temp & 0x01) && (!(temp&(1 << 16))));//等待时间到达 63 | SysTick->LOAD = 9000000;//1S 64 | } 65 | SysTick->CTRL = 0x00; //关闭计数器 66 | SysTick->VAL = 0X00; //清空计数器 67 | } 68 | 69 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/Delay.h: -------------------------------------------------------------------------------- 1 | /** 2 | *@file Delay.h 3 | *@author Neutree 4 | *@breif Delay Class 5 | *@copyright CQUT IOT Lib all rights reserved 6 | */ 7 | 8 | 9 | #ifndef __DELAY_H 10 | #define __DELAY_H 11 | #include "stm32f10x.h" 12 | 13 | class Delay 14 | { 15 | public: 16 | ///////////////////////// 17 | ///delay static function 18 | ///use Delay::Ms() or use object to invoke 19 | ///@param nMs the time will delay Unit:ms 20 | ///////////////////////// 21 | static void Ms(uint16_t nMs); 22 | 23 | ///////////////////////// 24 | ///delay static function 25 | ///use Delay::Us() or use object to invoke 26 | ///@param nUs the time will delay Unit:us 27 | ///////////////////////// 28 | static void Us(uint32_t nUs); 29 | ///////////////////////// 30 | ///delay static function 31 | ///use Delay::nS() or use object to invoke 32 | ///@param nS the time will delay Unit:nS 33 | ///////////////////////// 34 | static void S(uint32_t nS); 35 | }; 36 | 37 | 38 | #endif 39 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/F103_PWM.h: -------------------------------------------------------------------------------- 1 | #ifndef _F103_PWM_H_ 2 | #define _F103_PWM_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "stm32f10x_gpio.h" 6 | #include "stm32f10x_rcc.h" 7 | #include "stm32f10x_tim.h" 8 | 9 | class PWM{ 10 | 11 | private: 12 | TIM_TypeDef* mTimer; 13 | u16 mPsc; //分频系数 14 | u16 mArr; 15 | 16 | u16 mFrequency; //add by jason 17 | 18 | GPIO_InitTypeDef GPIO_InitStruct; //GPIO结构体 19 | TIM_TimeBaseInitTypeDef TIM_TimeBaseStruct; //时钟结构体 20 | TIM_OCInitTypeDef TIM_OCInitStructure; //定义输出结构体 21 | void PWMInit(TIM_TypeDef* timer, bool enCh1, bool enCh2, bool enCh3, bool enCh4, u16 frequency, u8 remap = 0); 22 | void Calcute(u16 frequency);//逐步毕竟频率,计算PSC和ARR; 23 | void Calcute2(u32 quo, u32 quo2, u32 rem2, bool flagBest);//重复的代码在一起; 24 | 25 | public: 26 | 27 | /** 28 | *@brief 构造函数 29 | *@param timer 选择的时钟 30 | *@param enCh1 通道1是否打开 31 | *@param enCh2 通道2是否打开 32 | *@param enCh3 通道3是否打开 33 | *@param enCh4 通道4是否打开 34 | *@param frequency 期望频率 35 | *@param remap 引脚是否映射,这个版本还没有做 36 | *@param remap 0: No Remap 1: ParialPinRemap 2:FullPinRemap 37 | */ 38 | PWM(TIM_TypeDef* timer, bool enCh1, bool enCh2, bool enCh3, bool enCh4, u16 frequency, u8 remap = 0) 39 | { 40 | mPsc = 0; 41 | mArr = 0; 42 | Calcute(frequency); 43 | mFrequency = frequency; //add by jason 44 | PWMInit(timer, enCh1, enCh2, enCh3, enCh4, frequency, remap); 45 | }; 46 | 47 | /** 48 | *@brief 改变一个通道的占空比 49 | *@param channel 选择通道 50 | *@param duty 设置占空比 51 | *@param isSetPositiveDuty 设置高电平的占空比还是设置低电平的占空比 52 | */ 53 | void SetDuty(u8 channel, float duty, bool isSetPositiveDuty = true); 54 | /** 55 | *@brief 改变通道的占空比 56 | *@param dutyCh1 设置通道1的占空比 57 | *@param dutyCh2 设置通道2的占空比 58 | *@param dutyCh3 设置通道3的占空比 59 | *@param dutyCh4 设置通道4的占空比 60 | *@param *@param isSetPositiveDuty 设置高电平的占空比还是设置低电平的占空比 61 | */ 62 | void SetDuty(float dutyCh1, float dutyCh2, float dutyCh3, float dutyCh4, bool isSetPositiveDuty = true);//重载 63 | 64 | /** 65 | *@brief 得到PWM的频率 66 | *@retval PWM频率 67 | */ 68 | u16 GetmFrequency();//Get the PWM's frequence.(add by jason) 69 | 70 | }; 71 | 72 | /* 73 | ** TIM对应的引脚 74 | ////////////////////////////////////// 75 | * TIM1还没加入库函数 76 | * TIM1_Ch1-----PA8 77 | * TIM1_Ch2-----PA9 78 | * TIM1_Ch3-----PA10 79 | * TIM1_Ch4-----PA11 80 | ///////////////////////////////////// 81 | 82 | * TIM2_Ch1-----PA0 83 | * TIM2_Ch2-----PA1 84 | * TIM2_Ch3-----PA2 85 | * TIM2_Ch4-----PA3 86 | 87 | * TIM3_Ch1-----PA6 ParialPinRemap PB4 88 | * TIM3_Ch2-----PA7 ParialPinRemap PB5 89 | * TIM3_Ch3-----PB0 90 | * TIM3_Ch4-----PB1 91 | 92 | * TIM4_Ch1-----PB6 93 | * TIM4_Ch2-----PB7 94 | * TIM4_Ch3-----PB8 95 | * TIM4_Ch4-----PB9 96 | 97 | */ 98 | 99 | #endif 100 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/Flash.h: -------------------------------------------------------------------------------- 1 | #ifndef __FLASH_H 2 | #define __FLASH_H 3 | 4 | #include "stm32f10x.h" 5 | #include "stm32f10x_flash.h" 6 | 7 | #define MEMORY_PAGE_SIZE (uint16_t)0x400 /* Page size = 1KByte */ 8 | 9 | 10 | /* Page status definitions */ 11 | #define MEMORY_STATUS_ERASED ((uint16_t)0xFFFF) /* PAGE is empty */ 12 | #define MEMORY_STATUS_RECEIVE_DATA ((uint16_t)0xEEEE) /* PAGE is marked to receive data */ 13 | #define MEMORY_STATUS_VALID_PAGE ((uint16_t)0x0000) /* PAGE containing valid data */ 14 | 15 | 16 | #define BYTE0(dwTemp) ( *( (char *)(&dwTemp) ) ) 17 | #define BYTE1(dwTemp) ( *( (char *)(&dwTemp) + 1) ) 18 | #define BYTE2(dwTemp) ( *( (char *)(&dwTemp) + 2) ) 19 | #define BYTE3(dwTemp) ( *( (char *)(&dwTemp) + 3) ) 20 | 21 | 22 | 23 | class flash 24 | { 25 | private: 26 | 27 | bool mUseHalfWord;//储存字长 16/32 默认16位 28 | uint32_t mStartAddress;//开始储存的地址 29 | public: 30 | /////////////////// 31 | ///构造函数 32 | ///@param startAddress 存储数据的开始位置 默认:0x08010000 即63k byte 处 33 | ///@param useHalfWord 单个数据储存的长度 true:16位 false:32位 默认:16位 34 | /////////////////// 35 | flash(uint32_t startAddress=(0x08000000+63*MEMORY_PAGE_SIZE),bool useHalfWord=true); 36 | 37 | 38 | /////////////////////// 39 | ///读取储存器中特定位置的值 40 | ///@param -relativeAddress 相对于开始地址的地址 41 | ///@param -Data 读出的数据存放的地址 42 | ///@retval -1 : 读取成功 -0:读取失败 43 | /////////////////////// 44 | bool Read(uint16_t relativeAddress, uint8_t* Data,u16 length); 45 | 46 | //position为一页中的位置,只能是偶数或者0 47 | bool Read(u16 pageNumber,u16 position,u16* data,u16 length); 48 | 49 | 50 | //bool Read(uint16_t relativeAddress, uint32_t* Data,u16 length); 51 | 52 | /////////////////////// 53 | ///向储存器中特定位置写值 54 | ///@param -pageNumber 相对于开始地址的页地址 55 | ///@param -Data 将要写入的数据 56 | ///@attention 如果构造构造函数的参数useHalfWord为true时,会现将其转换为u16再储存,否则会转换成u32再储存 57 | ///@retval -1 : 写入成功 -0:写入失败 58 | /////////////////////// 59 | bool Write(uint16_t pageNumber, uint8_t* Data,u16 length); 60 | 61 | //position为一页中的位置,只能是偶数或者0 ,当传入0的时候将擦除这一页 62 | bool Write(uint16_t pageNumber,u16 position,uint16_t* data,u16 length); 63 | 64 | bool Write(uint16_t pageNumber,u16 position,float data); 65 | float Read(uint16_t pageNumber,u16 position); 66 | 67 | bool Write(uint16_t pageNumber, uint32_t* Data,u16 length); 68 | 69 | 70 | //字符串的存储于读取,参数:页码,页码中位置,字符串 71 | bool Write(uint16_t pageNumber,u16 position,char* str); 72 | bool Read(uint16_t pageNumber,u16 position,char *str); 73 | bool Clear(uint16_t pageNumber); 74 | 75 | 76 | }; 77 | 78 | 79 | #endif 80 | 81 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/GPIO.cpp: -------------------------------------------------------------------------------- 1 | 2 | //include the header file containing the class declaration. 3 | #include "GPIO.h" 4 | 5 | 6 | //Initialize the static member constants 7 | const uint16_t GPIO::mPin[16] = { GPIO_Pin_0, GPIO_Pin_1, GPIO_Pin_2, GPIO_Pin_3, GPIO_Pin_4, GPIO_Pin_5, GPIO_Pin_6, GPIO_Pin_7, 8 | GPIO_Pin_8, GPIO_Pin_9, GPIO_Pin_10, GPIO_Pin_11, GPIO_Pin_12, GPIO_Pin_13, GPIO_Pin_14, GPIO_Pin_15 }; 9 | 10 | 11 | //The Constructor of the Class 12 | GPIO::GPIO(GPIO_TypeDef *port, uint16_t pin, GPIOMode_TypeDef mode, GPIOSpeed_TypeDef speed) :mMode(mode), mSpeed(speed), mPort(port), mSelectPin(pin) 13 | { 14 | GPIO_InitTypeDef GPIO_InitStructure; 15 | RCC_Configuration(); 16 | GPIO_InitStructure.GPIO_Pin = mPin[pin]; 17 | GPIO_InitStructure.GPIO_Speed = speed; 18 | GPIO_InitStructure.GPIO_Mode = mode; 19 | GPIO_Init(mPort, &GPIO_InitStructure); 20 | } 21 | 22 | //The function to configure the RCC of GPIO 23 | void GPIO::RCC_Configuration() 24 | { 25 | // SystemInit(); //系统设置初始化 26 | if (mPort == GPIOA) 27 | { 28 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); 29 | } 30 | else if (mPort == GPIOB) 31 | { 32 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); 33 | } 34 | else if (mPort == GPIOC) 35 | { 36 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE); 37 | } 38 | else if (mPort == GPIOD) 39 | { 40 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD, ENABLE); 41 | } 42 | else if (mPort == GPIOE) 43 | { 44 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOE, ENABLE); 45 | } 46 | else if (mPort == GPIOF) 47 | { 48 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF, ENABLE); 49 | } 50 | else if (mPort == GPIOG) 51 | { 52 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOG, ENABLE); 53 | } 54 | } 55 | 56 | /** 57 | * @brief Set the level of the pin 58 | * @param level:The level you wan to set,value:0 or 1 59 | */ 60 | void GPIO::SetLevel(u8 level) 61 | { 62 | if (level > 0) 63 | GPIO_SetBits(mPort, mPin[mSelectPin]); 64 | else 65 | GPIO_ResetBits(mPort, mPin[mSelectPin]); 66 | } 67 | 68 | /** 69 | * @brief Get the level of the pin 70 | * @retval level:Return the pin's level,value:true(1),false(0) 71 | */ 72 | bool GPIO::GetLevel() 73 | { 74 | if (!GPIO_ReadInputDataBit(mPort, mPin[mSelectPin])) 75 | return false; 76 | else 77 | return true; 78 | } 79 | 80 | /*** Invert the level of the pin ***/ 81 | void GPIO::Toggle() 82 | { 83 | if (GPIO_ReadInputDataBit(mPort, mPin[mSelectPin])) 84 | GPIO_ResetBits(mPort, mPin[mSelectPin]); 85 | else 86 | GPIO_SetBits(mPort, mPin[mSelectPin]); 87 | } 88 | 89 | void GPIO::ChangeMode(GPIOMode_TypeDef mode) 90 | { 91 | GPIO_InitTypeDef GPIO_InitStructure; 92 | 93 | GPIO_InitStructure.GPIO_Pin = mPin[mSelectPin]; 94 | GPIO_InitStructure.GPIO_Speed = mSpeed; 95 | GPIO_InitStructure.GPIO_Mode = mode; 96 | GPIO_Init(mPort, &GPIO_InitStructure); 97 | } 98 | 99 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/GPIO.h: -------------------------------------------------------------------------------- 1 | /* 2 | ********************************************************************************************************* 3 | * 4 | * GPIO CALSS HEADER FILE 5 | * 6 | * Filename : GPIO.h 7 | * Version : V1.0 8 | * Programmer(s) : Jason Xie 9 | * 10 | ********************************************************************************************************* 11 | */ 12 | #ifndef _GPIO_H 13 | #define _GPIO_H 14 | 15 | /** include header files **/ 16 | 17 | #include 18 | #include "stm32f10x_gpio.h" 19 | #include "stm32f10x_rcc.h" 20 | #include 21 | #include 22 | 23 | 24 | /** 25 | * @brief The class of GPIO. 26 | * @param mPin[16]: The array of GPIO_Pin_x. 27 | * @param mPort:The port of GPIO,such as GPIOA,etc. 28 | * @param mSelectPin:The pin you want to use. 29 | * @param mMode:The GPIO's mode,such as "GPIO_Mode_Out_PP",etc 30 | * @param mSpeed:The output's speed of GPIO,such as "GPIO_Speed_10MHz",etc 31 | */ 32 | class GPIO 33 | { 34 | private: 35 | static const uint16_t mPin[16]; 36 | 37 | GPIOMode_TypeDef mMode; 38 | GPIOSpeed_TypeDef mSpeed; 39 | 40 | /* The function to configure the RCC of GPIO */ 41 | void RCC_Configuration(); 42 | public: 43 | GPIO_TypeDef *mPort; 44 | uint16_t mSelectPin; 45 | 46 | /* The Constructor of the Class */ 47 | GPIO(GPIO_TypeDef *port = GPIOA, uint16_t pin = 1, GPIOMode_TypeDef mode = GPIO_Mode_Out_PP, GPIOSpeed_TypeDef speed = GPIO_Speed_50MHz); 48 | 49 | /** 50 | * @brief Set the pin as high level or low level. 51 | * @param level: The level you wan to set,type:unsigned char ,value:0 or 1 52 | */ 53 | void SetLevel(u8 level); 54 | 55 | /** 56 | * @brief Get the level of the pin. 57 | * @retval level:Return the pin's level,value:true(1),false(0) 58 | */ 59 | bool GetLevel(); 60 | 61 | /** 62 | * @brief Invert the level of the pin. 63 | */ 64 | void Toggle(); 65 | 66 | /** 67 | * @brief Change the GPIO's mode. 68 | * @param the GPIO's mode 69 | */ 70 | void ChangeMode(GPIOMode_TypeDef mode); 71 | }; 72 | 73 | 74 | #endif 75 | 76 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/Interrupt.h: -------------------------------------------------------------------------------- 1 | /** 2 | *@file Interrupt.h 3 | *@date 2015-10-27 4 | *@author 5 | *@breif interrupt management file 6 | * 7 | */ 8 | 9 | #ifndef __INTERRUPT_H 10 | #define __INTERRUPT_H 11 | 12 | /***************************************configuration********************************************/ 13 | #define USE_USART 14 | #define USE_I2C 15 | #define USE_SPI 16 | #define USE_NRF_IRQ 17 | /************************************configuration end********************************************/ 18 | 19 | #ifdef USE_NRF_IRQ 20 | #include "NRF24L01.h" 21 | extern NRF24L01 *pNRF; 22 | extern "C"{ 23 | void EXTI2_IRQHandler(void); 24 | } 25 | #endif 26 | 27 | #ifdef USE_USART 28 | #include "USART.h" 29 | extern USART *pUSART1; 30 | extern USART *pUSART2; 31 | extern USART *pUSART3; 32 | extern "C"{ 33 | void USART1_IRQHandler(void); 34 | void USART2_IRQHandler(void); 35 | void USART3_IRQHandler(void); 36 | 37 | } 38 | #endif 39 | 40 | #ifdef USE_I2C 41 | #include "I2C.h" 42 | extern I2C *pI2C1; 43 | extern I2C *pI2C2; 44 | extern "C"{ 45 | void I2C1_EV_IRQHandler(void); 46 | void I2C2_EV_IRQHandler(void); 47 | void I2C1_ER_IRQHandler(void); 48 | void I2C2_ER_IRQHandler(void); 49 | } 50 | #endif 51 | 52 | #ifdef USE_SPI 53 | #include "SPI.h" 54 | extern SPI *pSPI1; 55 | extern SPI *pSPI2; 56 | extern "C"{ 57 | void SPI1_IRQHandler(void); 58 | void SPI2_IRQHandler(void); 59 | } 60 | #endif 61 | 62 | extern "C"{ 63 | ////////////////////////////////// 64 | ///USART3 send channel 65 | ////////////////////////////////// 66 | void DMA1_Channel2_IRQHandler(); 67 | ///////////////////////////////// 68 | ///USART1 DMA send channel 69 | ///I2C2 DMA send channel 70 | ///////////////////////////////// 71 | void DMA1_Channel4_IRQHandler(); 72 | /////////////////////////////// 73 | ///I2C2 DMA receive channel 74 | ////////////////////////////// 75 | void DMA1_Channel5_IRQHandler(); 76 | 77 | /////////////////////////////// 78 | ///I2C1 DMA send channel 79 | ////////////////////////////// 80 | void DMA1_Channel6_IRQHandler(); 81 | 82 | ///////////////////////////////// 83 | ///USART2 DMA send channel 84 | ///I2C1 DMA receive channel 85 | //////////////////////////////// 86 | void DMA1_Channel7_IRQHandler(); 87 | } 88 | 89 | #endif 90 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/LED.cpp: -------------------------------------------------------------------------------- 1 | #include "LED.h" 2 | 3 | 4 | ///构造函数 5 | ///@param gpio GPIO类对象,分配片上资源 6 | ///@param highLevelOn 是否输出高电平时为LED打开 7 | ///////////////////////// 8 | LED::LED(GPIO &gpio, bool highLevelOn) 9 | :mGPIO(gpio) 10 | { 11 | if (highLevelOn) 12 | mLevelOn = 1; 13 | else 14 | mLevelOn = 0; 15 | } 16 | 17 | 18 | //////////////////////// 19 | ///翻转(开-->关 , 关-->开) 20 | /////////////////////// 21 | void LED::Toggle() 22 | { 23 | if (mGPIO.GetLevel()) 24 | mGPIO.SetLevel(0); 25 | else 26 | mGPIO.SetLevel(1); 27 | } 28 | 29 | ////////////////////// 30 | ///打开LED 31 | ///////////////////// 32 | void LED::On() 33 | { 34 | mGPIO.SetLevel(mLevelOn); 35 | } 36 | 37 | ///////////////////// 38 | ///关闭LED 39 | //////////////////// 40 | void LED::Off() 41 | { 42 | mGPIO.SetLevel(mLevelOn ^ 1); 43 | } 44 | 45 | //////////////////////// 46 | ///闪烁n次 47 | ///@param time 闪烁次数 48 | ///@param Interval 闪烁间隔 (ms) 49 | /////////////////////// 50 | void LED::Blink(uint8_t time, uint16_t interval) 51 | { 52 | for (uint8_t i = 0; i < time; ++i) 53 | { 54 | On(); 55 | TaskManager::DelayMs(interval); 56 | Off(); 57 | TaskManager::DelayMs(interval); 58 | } 59 | } 60 | //////////////////////// 61 | ///两个灯一起闪烁n次 62 | ///@param 另一个灯的引用 63 | ///@param time 闪烁次数 64 | ///@param Interval 闪烁间隔(ms) 65 | /////////////////////// 66 | void LED::Blink2(LED &led, uint8_t time, uint16_t interval) 67 | { 68 | for (uint8_t i = 0; i < time; ++i) 69 | { 70 | On(); 71 | led.On(); 72 | TaskManager::DelayMs(interval); 73 | Off(); 74 | led.Off(); 75 | TaskManager::DelayMs(interval); 76 | } 77 | } 78 | 79 | //////////////////////// 80 | ///两个灯交替闪烁n次 81 | ///@param 另一个灯的引用 82 | ///@param time 闪烁次数 83 | ///@param Interval 闪烁间隔(ms) 84 | /////////////////////// 85 | void LED::Blink3(LED &led, uint8_t time, uint16_t interval) 86 | { 87 | for (uint8_t i = 0; i < time; ++i) 88 | { 89 | On(); 90 | led.Off(); 91 | TaskManager::DelayMs(interval); 92 | Off(); 93 | led.On(); 94 | TaskManager::DelayMs(interval); 95 | } 96 | led.Off(); 97 | } 98 | 99 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/LED.h: -------------------------------------------------------------------------------- 1 | #ifndef _LED_H 2 | #define _LED_H 3 | 4 | #include "GPIO.h" 5 | #include "TaskManager.h" 6 | class LED 7 | { 8 | public: 9 | //////////////////////// 10 | ///构造函数 11 | ///@param gpio GPIO类对象,分配片上资源 12 | ///@param highLevelOn 是否输出高电平时为LED打开 13 | ///////////////////////// 14 | LED(GPIO &gpio, bool highLevelOn = true); 15 | 16 | 17 | //////////////////////// 18 | ///翻转(开-->关 , 关-->开) 19 | /////////////////////// 20 | void Toggle(); 21 | 22 | ////////////////////// 23 | ///打开LED 24 | ///////////////////// 25 | void On(); 26 | 27 | ///////////////////// 28 | ///关闭LED 29 | //////////////////// 30 | void Off(); 31 | 32 | //////////////////////// 33 | ///闪烁n次 34 | ///@param time 闪烁次数 35 | ///@param Interval 闪烁间隔(ms) 36 | /////////////////////// 37 | void Blink(uint8_t time, uint16_t interval); 38 | 39 | //////////////////////// 40 | ///两个灯一起闪烁n次 41 | ///@param 另一个灯的引用 42 | ///@param time 闪烁次数 43 | ///@param Interval 闪烁间隔(ms) 44 | /////////////////////// 45 | void Blink2(LED &led, uint8_t time, uint16_t interval); 46 | 47 | 48 | //////////////////////// 49 | ///两个灯交替闪烁n次 50 | ///@param 另一个灯的引用 51 | ///@param time 闪烁次数 52 | ///@param Interval 闪烁间隔(ms) 53 | /////////////////////// 54 | void Blink3(LED &led, uint8_t time, uint16_t interval); 55 | 56 | private: 57 | ////////////////////////// 58 | ///GPIO的类的实例对象引用 59 | ////////////////////////// 60 | GPIO & mGPIO; 61 | //////////////////////// 62 | ///标志开启LED时取的电平高低 63 | //////////////////////// 64 | unsigned char mLevelOn; 65 | 66 | 67 | 68 | }; 69 | 70 | 71 | #endif 72 | 73 | 74 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/NRF24L01.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/NRF24L01.cpp -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/NRF24L01.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/NRF24L01.h -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/SPI.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/SPI.cpp -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/SPI.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/SPI.h -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/Sensor.h: -------------------------------------------------------------------------------- 1 | #ifndef _SENSOR_H_ 2 | #define _SENSOR_H_ 3 | 4 | #include "TaskManager.h" 5 | 6 | class Sensor 7 | { 8 | protected: 9 | bool mHealthy; 10 | bool mIsUpdated; //I2C task complete falg 11 | double mUpdatedTime; //I2C task completed time (second) 12 | double mInterval; //time interval since last update (second) 13 | public: 14 | Sensor() 15 | { 16 | mHealthy = false; 17 | mIsUpdated = true; 18 | mUpdatedTime = 0; 19 | mInterval = 0; 20 | } 21 | void Updated() 22 | { 23 | mIsUpdated = true; 24 | double curTime = tskmgr.Time(); 25 | mInterval = curTime - mUpdatedTime; 26 | mUpdatedTime = curTime; 27 | } 28 | float Interval() { return mInterval; } //return interval between two update 29 | bool IsHealthy() { return mHealthy; } //return healthy state of device 30 | }; 31 | 32 | 33 | #endif 34 | 35 | 36 | 37 | 38 | 39 | 40 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/TaskManager.cpp: -------------------------------------------------------------------------------- 1 | #include "TaskManager.h" 2 | 3 | TaskManager tskmgr; 4 | 5 | double TaskManager::_it_time = 0; 6 | double TaskManager::_new_time = 0; 7 | double TaskManager::_old_time = 0; 8 | 9 | //Constructor 10 | TaskManager::TaskManager() 11 | { 12 | SysTick->CTRL &= 0xFFFFFFFB; //Clock div 8 = 9M 13 | SysTick->LOAD = 16200000; //1.8s 14 | SysTick->CTRL |= 0x00000003; //INT +ENABLE 15 | } 16 | //get current time since power on 17 | double TaskManager::Time(void) 18 | { 19 | _new_time = _it_time + 1.8 - SysTick->VAL / 9000000.0; //update current time 20 | 21 | if (_new_time - _old_time > 1.799) //check if breaked by SysTick interrupt 22 | { 23 | _new_time -= 1.8; //calibrate current time 24 | } 25 | _old_time = _new_time; //update old time 26 | return _new_time; 27 | } 28 | 29 | //微秒延时 30 | void TaskManager::DelayUs(u16 nus) 31 | { 32 | double OldT = Time(); 33 | while ((Time() - OldT) < double(nus) / 1000000.0); 34 | } 35 | 36 | //毫秒延时 37 | void TaskManager::DelayMs(u16 nms) 38 | { 39 | double OldT = Time(); 40 | while ((Time() - OldT) < double(nms) / 1000.0); 41 | } 42 | 43 | void TaskManager::DelayS(u16 ns) 44 | { 45 | double OldT = Time(); 46 | while ((Time() - OldT) < double(ns)); 47 | } 48 | 49 | bool TaskManager::TimeSlice(double &record, double timeout) 50 | { 51 | double NowTime = Time(); 52 | if (NowTime - record >= timeout) 53 | { 54 | record = Time(); //更新记录 55 | return true; 56 | } 57 | else 58 | return false; 59 | } 60 | 61 | 62 | //SysTick interrupt IRQ handler 63 | extern "C" 64 | { 65 | void SysTick_Handler(void) 66 | { 67 | TaskManager::_it_time += 1.8; 68 | } 69 | } 70 | 71 | 72 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/TaskManager.h: -------------------------------------------------------------------------------- 1 | #ifndef _TASK_MANAGER_H_ 2 | #define _TASK_MANAGER_H_ 3 | #include "stm32f10x.h" 4 | 5 | class TaskManager 6 | { 7 | private: 8 | static double _new_time; //current updated time 9 | static double _old_time; //last updated time 10 | public: 11 | static double _it_time; //time = SysTick interrupt counter*1.8s 12 | public: 13 | TaskManager(); //constructor 14 | static double Time(void); //get current time 15 | static void DelayUs(u16 nus); 16 | static void DelayMs(u16 nms); 17 | static void DelayS(u16 ns); 18 | static bool TimeSlice(double &record, double timeout); //传入一个时间记录值和一个超时时间 记录达到了超时时间返回tree 19 | }; 20 | extern TaskManager tskmgr; 21 | 22 | #define MOD_ERROR 0x00 23 | #define MOD_READY 0x01 24 | #define MOD_BUSY 0x02 25 | #define MOD_LOCK 0x04 26 | #define MOD_UNLOCK 0x08 27 | 28 | 29 | #endif 30 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/Timer.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file Timer.h 4 | * @author lissettecarlr 5 | * @version V1.0 6 | V1.1 增加开关中断功能 7 | V1.2 增加清除CNT计数器的值的功能 8 | 9 | * @date 10/25/2015(create) 10 | 10/28/2015(Debug) 11 | 11/02/2015(add) 12 | * @brief 必须配套Interrupt文件使用,用户如需需要编写中断函数,直接编写 13 | TIMX CH1 CH2 CH3 CH4 14 | 1 PA8 PA9 PA10 PA11 15 | 2 PA0 PA1 PA2 PA3 16 | 3 PA6 PA7 PB0 PB1 17 | 4 PB6 PB7 PB8 PB9 18 | ****************************************************************************** 19 | */ 20 | 21 | #ifndef __TIMER_H 22 | #define __TIMER_H 23 | 24 | /* Includes ------------------------------------------------------------------*/ 25 | extern "C"{ 26 | #include "stm32f10x.h" 27 | } 28 | 29 | /* define -------------------------------------------------------------------*/ 30 | //#define COEFFICIENT 66446 31 | #define COEFFICIENT 911 32 | // 65535/72 33 | /* class----------------------------------------------------------------------*/ 34 | 35 | class Timer{ 36 | private: 37 | u16 mArr;//计数器初值 38 | u16 mPsc;//计数器预分频 39 | TIM_TypeDef *mTempTimer;//时钟选择 40 | void Conversion(u16 s, u16 ms, u16 us);//将时分秒转换为初值和预分频 41 | 42 | public: 43 | //////////////////////////////////////// 44 | ///定时器初始化,默认定时器1,定时1ms 45 | ///@param timer 选择使用的定时器 46 | ///@param Prioritygroup 中断分组 47 | ///@param preemprionPriority 抢占优先级 48 | ///@param subPriority 响应优先级 49 | ///@param second 秒 50 | ///@param millisecond 毫秒 51 | ///@param microsecond 微秒 52 | //////////////////////////////////////// 53 | Timer(TIM_TypeDef *timer = TIM1, u8 Prioritygroup = 2, u8 preemprionPriority = 2, u8 subPriority = 2 54 | , u16 second = 0, u16 millisecond = 1, u16 microsecond = 0); 55 | 56 | //////////////////// 57 | ///开启定时器 58 | /////////////////// 59 | void Start(); 60 | 61 | /////////////////// 62 | ///关闭定时器 63 | ////////////////// 64 | void Stop(); 65 | ///////////////////////////////////////// 66 | ///开关中断 67 | ///@param bool true 开启中断 false 关闭中断 68 | ////////////////////////////////////////// 69 | void OnOrOffIrq(bool Switch); 70 | 71 | /////////////////// 72 | ///清空计数器的值 73 | ////////////////// 74 | void ClearCNT(void); 75 | 76 | 77 | /////////////////////////////////////////////// 78 | ///得到该时刻定时器循环到的时间 79 | ///@retval 时间,单位us,范围是0到初始设置时间 80 | /////////////////////////////////////////////// 81 | u32 GetNowTime(void); 82 | 83 | /** 84 | * @brief 得到所使用的计时器 85 | * @retval 返回所使用的计时器 86 | * @author jason 87 | */ 88 | TIM_TypeDef* GetTIMx(void); 89 | 90 | 91 | /** 92 | * @brief 重新设定计时器 93 | * @param s 秒、 94 | * @param ms 毫秒 95 | * @param us 微秒 96 | * @author jason 97 | */ 98 | void ResetTimer(u16 s, u16 ms, u16 us); 99 | 100 | /** 101 | * @brief 得到所使用的计时器的ARR寄存器的值 102 | * @retval 返回所使用的计时器的ARR寄存器的值 103 | * @author jason 104 | */ 105 | u16 GetTimerArr(); 106 | 107 | /** 108 | * @brief 得到所使用的计时器的Psc寄存器的值 109 | * @retval 返回所使用的计时器的Psc寄存器的值 110 | * @author jason 111 | */ 112 | u16 GetTimerPsc(); 113 | }; 114 | 115 | #endif 116 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/Lib/eeprom.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file EEPROM_Emulation/inc/eeprom.h 4 | * @author MCD Application Team 5 | * @version V3.1.0 6 | * @date 07/27/2009 7 | * @brief This file contains all the functions prototypes for the EEPROM 8 | * emulation firmware library. 9 | ****************************************************************************** 10 | * @copy 11 | * 12 | * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS 13 | * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE 14 | * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY 15 | * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING 16 | * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE 17 | * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. 18 | * 19 | *

© COPYRIGHT 2009 STMicroelectronics

20 | */ 21 | 22 | /* Define to prevent recursive inclusion -------------------------------------*/ 23 | #ifndef __EEPROM_H 24 | #define __EEPROM_H 25 | 26 | /* Includes ------------------------------------------------------------------*/ 27 | #include "stm32f10x.h" 28 | 29 | /* Exported constants --------------------------------------------------------*/ 30 | /* Define the STM32F10Xxx Flash page size depending on the used STM32 device */ 31 | #if defined (STM32F10X_LD) || defined (STM32F10X_MD) 32 | #define PAGE_SIZE (uint16_t)0x400 /* Page size = 1KByte */ 33 | #elif defined (STM32F10X_HD) || defined (STM32F10X_CL) 34 | #define PAGE_SIZE (uint16_t)0x800 /* Page size = 2KByte */ 35 | #endif 36 | 37 | /* EEPROM start address in Flash */ 38 | #define EEPROM_START_ADDRESS ((uint32_t)0x08010000) /* EEPROM emulation start address: 39 | after 64KByte of used Flash memory */ 40 | 41 | /* Pages 0 and 1 base and end addresses */ 42 | #define PAGE0_BASE_ADDRESS ((uint32_t)(EEPROM_START_ADDRESS + 0x000)) 43 | #define PAGE0_END_ADDRESS ((uint32_t)(EEPROM_START_ADDRESS + (PAGE_SIZE - 1))) 44 | 45 | #define PAGE1_BASE_ADDRESS ((uint32_t)(EEPROM_START_ADDRESS + PAGE_SIZE)) 46 | #define PAGE1_END_ADDRESS ((uint32_t)(EEPROM_START_ADDRESS + (2 * PAGE_SIZE - 1))) 47 | 48 | /* Used Flash pages for EEPROM emulation */ 49 | #define PAGE0 ((uint16_t)0x0000) 50 | #define PAGE1 ((uint16_t)0x0001) 51 | 52 | /* No valid page define */ 53 | #define NO_VALID_PAGE ((uint16_t)0x00AB) 54 | 55 | /* Page status definitions */ 56 | #define ERASED ((uint16_t)0xFFFF) /* PAGE is empty */ 57 | #define RECEIVE_DATA ((uint16_t)0xEEEE) /* PAGE is marked to receive data */ 58 | #define VALID_PAGE ((uint16_t)0x0000) /* PAGE containing valid data */ 59 | 60 | /* Valid pages in read and write defines */ 61 | #define READ_FROM_VALID_PAGE ((uint8_t)0x00) 62 | #define WRITE_IN_VALID_PAGE ((uint8_t)0x01) 63 | 64 | /* Page full define */ 65 | #define PAGE_FULL ((uint8_t)0x80) 66 | 67 | /* Variables' number */ 68 | #define NumbOfVar ((uint8_t)57) 69 | 70 | /* Virtual address defined by the user: 0xFFFF value is prohibited */ 71 | extern uint16_t VirtAddVarTab[NumbOfVar]; 72 | 73 | 74 | /* Exported types ------------------------------------------------------------*/ 75 | /* Exported macro ------------------------------------------------------------*/ 76 | /* Exported functions ------------------------------------------------------- */ 77 | uint16_t EE_Init(void); 78 | uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data); 79 | uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data); 80 | 81 | #endif /* __EEPROM_H */ 82 | 83 | /******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ 84 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/RTE/RTE_Components.h: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | * Auto generated Run-Time-Environment Component Configuration File 4 | * *** Do not modify ! *** 5 | * 6 | * Project: 'FourAxisByStm32' 7 | * Target: 'Target 1' 8 | */ 9 | 10 | #ifndef RTE_COMPONENTS_H 11 | #define RTE_COMPONENTS_H 12 | 13 | #define RTE_DEVICE_STDPERIPH_DMA 14 | #define RTE_DEVICE_STDPERIPH_EXTI 15 | #define RTE_DEVICE_STDPERIPH_FLASH 16 | #define RTE_DEVICE_STDPERIPH_FRAMEWORK 17 | #define RTE_DEVICE_STDPERIPH_GPIO 18 | #define RTE_DEVICE_STDPERIPH_I2C 19 | #define RTE_DEVICE_STDPERIPH_RCC 20 | #define RTE_DEVICE_STDPERIPH_SPI 21 | #define RTE_DEVICE_STDPERIPH_TIM 22 | #define RTE_DEVICE_STDPERIPH_USART 23 | 24 | #endif /* RTE_COMPONENTS_H */ 25 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/两机通讯(中断)/FourAxisByStm32(接收)/main.cpp -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/demo/RTE/RTE_Components.h: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | * Auto generated Run-Time-Environment Component Configuration File 4 | * *** Do not modify ! *** 5 | * 6 | * Project: 'NRF24L01' 7 | * Target: 'Target 1' 8 | */ 9 | 10 | #ifndef RTE_COMPONENTS_H 11 | #define RTE_COMPONENTS_H 12 | 13 | #define RTE_DEVICE_STDPERIPH_DMA 14 | #define RTE_DEVICE_STDPERIPH_EXTI 15 | #define RTE_DEVICE_STDPERIPH_FRAMEWORK 16 | #define RTE_DEVICE_STDPERIPH_GPIO 17 | #define RTE_DEVICE_STDPERIPH_I2C 18 | #define RTE_DEVICE_STDPERIPH_RCC 19 | #define RTE_DEVICE_STDPERIPH_SPI 20 | #define RTE_DEVICE_STDPERIPH_TIM 21 | #define RTE_DEVICE_STDPERIPH_USART 22 | 23 | #endif /* RTE_COMPONENTS_H */ 24 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/demo/main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/demo/main.cpp -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/Delay.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | *@file Delay.cpp 3 | *@author Neutree 4 | *@breif Delay Class 5 | *@copyright CQUT IOT Lib all rights reserved 6 | */ 7 | 8 | #include "Delay.h" 9 | 10 | 11 | 12 | 13 | void Delay::Ms(uint16_t nms) 14 | { 15 | 16 | #ifdef DELAY_USE_SYSTICK 17 | u32 temp; 18 | if(nms==0) 19 | return; 20 | SysTick->LOAD = 9000*nms; 21 | SysTick->VAL=0X00;//清空计数器 22 | SysTick->CTRL=0X01;//使能,减到零是无动作,采用外部时钟源 23 | do 24 | { 25 | temp=SysTick->CTRL;//读取当前倒计数值 26 | }while((temp&0x01)&&(!(temp&(1<<16))));//等待时间到达 27 | SysTick->CTRL=0x00; //关闭计数器 28 | SysTick->VAL =0X00; //清空计数器 29 | #else 30 | u16 i=0; 31 | while(nms--) 32 | { 33 | i=8000; //自己定义 34 | while(i--) ; 35 | } 36 | #endif 37 | } 38 | 39 | 40 | void Delay::Us(uint32_t usec) 41 | { 42 | u32 temp; 43 | #ifdef DELAY_USE_SYSTICK 44 | if(nus==0) 45 | return; 46 | SysTick->LOAD = 9*usec; 47 | SysTick->VAL=0X00;//清空计数器 48 | SysTick->CTRL=0X01;//使能,减到零是无动作,采用外部时钟源 49 | do 50 | { 51 | temp=SysTick->CTRL;//读取当前倒计数值 52 | }while((temp&0x01)&&(!(temp&(1<<16))));//等待时间到达 53 | 54 | SysTick->CTRL=0x00; //关闭计数器 55 | SysTick->VAL =0X00; //清空计数器 56 | 57 | #else 58 | u16 i=0; 59 | while(temp--) 60 | { 61 | i=10; //自己定义 62 | while(i--) ; 63 | } 64 | #endif 65 | } 66 | 67 | 68 | 69 | void Delay::S(uint32_t ns) 70 | { 71 | u32 temp; 72 | #ifdef DELAY_USE_SYSTICK 73 | u32 i; 74 | if(ns==0) 75 | return; 76 | SysTick->LOAD = 9000000;//1S 77 | SysTick->VAL=0X00;//清空计数器 78 | SysTick->CTRL=0X01;//使能,减到零是无动作,采用外部时钟源 79 | for(i=0;iCTRL;//读取当前倒计数值 84 | }while((temp&0x01)&&(!(temp&(1<<16))));//等待时间到达 85 | SysTick->LOAD = 9000000;//1S 86 | } 87 | SysTick->CTRL=0x00; //关闭计数器 88 | SysTick->VAL =0X00; //清空计数器 89 | #else 90 | while(temp--) 91 | { 92 | Ms(1000); 93 | } 94 | #endif 95 | } 96 | 97 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/Delay.h: -------------------------------------------------------------------------------- 1 | /** 2 | *@file Delay.h 3 | *@author Neutree 4 | *@breif Delay Class 5 | *@copyright CQUT IOT Lib all rights reserved 6 | */ 7 | 8 | 9 | #ifndef __DELAY_H 10 | #define __DELAY_H 11 | 12 | /*************************configuration******************************/ 13 | // #define DELAY_USE_SYSTICK 14 | #define DELAY_USE_SOFTDELAY 15 | 16 | /********************************************************************/ 17 | 18 | #include "stm32f10x.h" 19 | 20 | class Delay 21 | { 22 | public: 23 | ///////////////////////// 24 | ///delay static function 25 | ///use Delay::Ms() or use object to invoke 26 | ///@param nMs the time will delay Unit:ms 27 | ///////////////////////// 28 | static void Ms(uint16_t nMs); 29 | 30 | ///////////////////////// 31 | ///delay static function 32 | ///use Delay::Us() or use object to invoke 33 | ///@param nUs the time will delay Unit:us 34 | ///////////////////////// 35 | static void Us(uint32_t nUs); 36 | ///////////////////////// 37 | ///delay static function 38 | ///use Delay::nS() or use object to invoke 39 | ///@param nS the time will delay Unit:nS 40 | ///////////////////////// 41 | static void S(uint32_t nS); 42 | }; 43 | 44 | 45 | #endif 46 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/F103_PWM.h: -------------------------------------------------------------------------------- 1 | #ifndef _F103_PWM_H_ 2 | #define _F103_PWM_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "stm32f10x_gpio.h" 6 | #include "stm32f10x_rcc.h" 7 | #include "stm32f10x_tim.h" 8 | 9 | class PWM{ 10 | 11 | private: 12 | TIM_TypeDef* mTimer; 13 | u16 mPsc; //分频系数 14 | u16 mArr; 15 | 16 | u16 mFrequency; //add by jason 17 | 18 | GPIO_InitTypeDef GPIO_InitStruct; //GPIO结构体 19 | TIM_TimeBaseInitTypeDef TIM_TimeBaseStruct; //时钟结构体 20 | TIM_OCInitTypeDef TIM_OCInitStructure; //定义输出结构体 21 | void PWMInit(TIM_TypeDef* timer, bool enCh1, bool enCh2, bool enCh3, bool enCh4, u16 frequency, u8 remap = 0); 22 | void Calcute(u16 frequency);//逐步毕竟频率,计算PSC和ARR; 23 | void Calcute2(u32 quo, u32 quo2, u32 rem2, bool flagBest);//重复的代码在一起; 24 | 25 | public: 26 | 27 | /** 28 | *@brief 构造函数 29 | *@param timer 选择的时钟 30 | *@param enCh1 通道1是否打开 31 | *@param enCh2 通道2是否打开 32 | *@param enCh3 通道3是否打开 33 | *@param enCh4 通道4是否打开 34 | *@param frequency 期望频率 35 | *@param remap 引脚是否映射,这个版本还没有做 36 | *@param remap 0: No Remap 1: ParialPinRemap 2:FullPinRemap 37 | */ 38 | PWM(TIM_TypeDef* timer, bool enCh1, bool enCh2, bool enCh3, bool enCh4, u16 frequency, u8 remap = 0) 39 | { 40 | mPsc = 0; 41 | mArr = 0; 42 | Calcute(frequency); 43 | mFrequency = frequency; //add by jason 44 | PWMInit(timer, enCh1, enCh2, enCh3, enCh4, frequency, remap); 45 | }; 46 | 47 | /** 48 | *@brief 改变一个通道的占空比 49 | *@param channel 选择通道 50 | *@param duty 设置占空比 51 | *@param isSetPositiveDuty 设置高电平的占空比还是设置低电平的占空比 52 | */ 53 | void SetDuty(u8 channel, float duty, bool isSetPositiveDuty = true); 54 | /** 55 | *@brief 改变通道的占空比 56 | *@param dutyCh1 设置通道1的占空比 57 | *@param dutyCh2 设置通道2的占空比 58 | *@param dutyCh3 设置通道3的占空比 59 | *@param dutyCh4 设置通道4的占空比 60 | *@param *@param isSetPositiveDuty 设置高电平的占空比还是设置低电平的占空比 61 | */ 62 | void SetDuty(float dutyCh1, float dutyCh2, float dutyCh3, float dutyCh4, bool isSetPositiveDuty = true);//重载 63 | 64 | /** 65 | *@brief 得到PWM的频率 66 | *@retval PWM频率 67 | */ 68 | u16 GetmFrequency();//Get the PWM's frequence.(add by jason) 69 | 70 | }; 71 | 72 | /* 73 | ** TIM对应的引脚 74 | ////////////////////////////////////// 75 | * TIM1还没加入库函数 76 | * TIM1_Ch1-----PA8 77 | * TIM1_Ch2-----PA9 78 | * TIM1_Ch3-----PA10 79 | * TIM1_Ch4-----PA11 80 | ///////////////////////////////////// 81 | 82 | * TIM2_Ch1-----PA0 83 | * TIM2_Ch2-----PA1 84 | * TIM2_Ch3-----PA2 85 | * TIM2_Ch4-----PA3 86 | 87 | * TIM3_Ch1-----PA6 ParialPinRemap PB4 88 | * TIM3_Ch2-----PA7 ParialPinRemap PB5 89 | * TIM3_Ch3-----PB0 90 | * TIM3_Ch4-----PB1 91 | 92 | * TIM4_Ch1-----PB6 93 | * TIM4_Ch2-----PB7 94 | * TIM4_Ch3-----PB8 95 | * TIM4_Ch4-----PB9 96 | 97 | */ 98 | 99 | #endif 100 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/GPIO.cpp: -------------------------------------------------------------------------------- 1 | 2 | //include the header file containing the class declaration. 3 | #include "GPIO.h" 4 | 5 | 6 | //Initialize the static member constants 7 | const uint16_t GPIO::mPin[16]={GPIO_Pin_0,GPIO_Pin_1,GPIO_Pin_2,GPIO_Pin_3,GPIO_Pin_4,GPIO_Pin_5,GPIO_Pin_6,GPIO_Pin_7, 8 | GPIO_Pin_8,GPIO_Pin_9,GPIO_Pin_10,GPIO_Pin_11,GPIO_Pin_12,GPIO_Pin_13,GPIO_Pin_14,GPIO_Pin_15}; 9 | 10 | 11 | //The Constructor of the Class 12 | GPIO::GPIO(GPIO_TypeDef *port,uint16_t pin,GPIOMode_TypeDef mode,GPIOSpeed_TypeDef speed):mMode(mode),mSpeed(speed),mPort(port),mSelectPin(pin) 13 | { 14 | GPIO_InitTypeDef GPIO_InitStructure; 15 | RCC_Configuration(); 16 | GPIO_InitStructure.GPIO_Pin=mPin[pin]; 17 | GPIO_InitStructure.GPIO_Speed=speed; 18 | GPIO_InitStructure.GPIO_Mode=mode; 19 | GPIO_Init(mPort,&GPIO_InitStructure); 20 | } 21 | 22 | //The function to configure the RCC of GPIO 23 | void GPIO::RCC_Configuration() 24 | { 25 | // SystemInit(); //系统设置初始化 26 | if(mPort==GPIOA) 27 | { 28 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA,ENABLE); 29 | } 30 | else if(mPort==GPIOB) 31 | { 32 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB,ENABLE); 33 | } 34 | else if(mPort==GPIOC) 35 | { 36 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC,ENABLE); 37 | } 38 | else if(mPort==GPIOD) 39 | { 40 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD,ENABLE); 41 | } 42 | else if(mPort==GPIOE) 43 | { 44 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOE,ENABLE); 45 | } 46 | else if(mPort==GPIOF) 47 | { 48 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF,ENABLE); 49 | } 50 | else if(mPort==GPIOG) 51 | { 52 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOG,ENABLE); 53 | } 54 | } 55 | 56 | /** 57 | * @brief Set the level of the pin 58 | * @param level:The level you wan to set,value:0 or 1 59 | */ 60 | void GPIO::SetLevel(u8 level) 61 | { 62 | if(level>0) 63 | GPIO_SetBits(mPort,mPin[mSelectPin]); 64 | else 65 | GPIO_ResetBits(mPort,mPin[mSelectPin]); 66 | } 67 | 68 | /** 69 | * @brief Get the level of the pin 70 | * @retval level:Return the pin's level,value:true(1),false(0) 71 | */ 72 | bool GPIO::GetLevel() 73 | { 74 | if(!GPIO_ReadInputDataBit(mPort,mPin[mSelectPin])) 75 | return false; 76 | else 77 | return true; 78 | } 79 | 80 | /*** Invert the level of the pin ***/ 81 | void GPIO::Toggle() 82 | { 83 | if(GPIO_ReadInputDataBit(mPort,mPin[mSelectPin])) 84 | GPIO_ResetBits(mPort,mPin[mSelectPin]); 85 | else 86 | GPIO_SetBits(mPort,mPin[mSelectPin]); 87 | } 88 | 89 | void GPIO::ChangeMode(GPIOMode_TypeDef mode) 90 | { 91 | GPIO_InitTypeDef GPIO_InitStructure; 92 | 93 | GPIO_InitStructure.GPIO_Pin = mPin[mSelectPin]; 94 | GPIO_InitStructure.GPIO_Speed = mSpeed; 95 | GPIO_InitStructure.GPIO_Mode = mode; 96 | GPIO_Init(mPort,&GPIO_InitStructure); 97 | } 98 | 99 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/GPIO.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/GPIO.h -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/Interrupt.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | *@file Interrupt.h 3 | *@date 2015-10-27 4 | *@author 5 | *@breif interrupt management file 6 | * 7 | */ 8 | 9 | #include "Interrupt.h" 10 | 11 | /********************************************USART INTERRUPT****************************************************/ 12 | #ifdef USE_USART 13 | USART *pUSART1 = 0; 14 | USART *pUSART2 = 0; 15 | USART *pUSART3 = 0; 16 | void USART1_IRQHandler(void) 17 | { 18 | if(pUSART1) 19 | pUSART1->Irq(); 20 | } 21 | void USART2_IRQHandler(void) 22 | { 23 | if(pUSART2) 24 | pUSART2->Irq(); 25 | } 26 | void USART3_IRQHandler(void) 27 | { 28 | if(pUSART3) 29 | pUSART3->Irq(); 30 | } 31 | #endif 32 | /********************************************USART INTERRUP END**********************************************/ 33 | 34 | 35 | /*****************************************I2C EVENT AND ERROR INTERRUPT**************************************/ 36 | #ifdef USE_I2C 37 | I2C *pI2C1 = 0; 38 | I2C *pI2C2 = 0; 39 | 40 | void I2C1_EV_IRQHandler(void) 41 | { 42 | if(pI2C1) 43 | pI2C1->EventIRQ(); 44 | } 45 | void I2C2_EV_IRQHandler(void) 46 | { 47 | if(pI2C2) 48 | pI2C2->EventIRQ(); 49 | } 50 | void I2C1_ER_IRQHandler(void) 51 | { 52 | if(pI2C1) 53 | pI2C1->ErrorIRQ(); 54 | } 55 | void I2C2_ER_IRQHandler(void) 56 | { 57 | if(pI2C2) 58 | pI2C2->ErrorIRQ(); 59 | } 60 | #endif 61 | /***********************************I2C EVENT AND ERROR INTERRUPT END **************************************/ 62 | 63 | /*********************************** DMA INTERRUPT ********************************************************/ 64 | ////////////////////////////////// 65 | ///USART3 send channel 66 | ////////////////////////////////// 67 | void DMA1_Channel2_IRQHandler() 68 | { 69 | #ifdef USE_USART 70 | if(pUSART3) 71 | pUSART3->DmaIrq(); 72 | #endif 73 | } 74 | 75 | 76 | ///////////////////////////////// 77 | ///USART1 DMA send channel 78 | ///I2C2 DMA send channel 79 | ///////////////////////////////// 80 | void DMA1_Channel4_IRQHandler() 81 | { 82 | #ifdef USE_USART 83 | if(pUSART1) 84 | pUSART1->DmaIrq(); 85 | #endif 86 | #ifdef USE_I2C 87 | #ifdef I2C_USE_DMA 88 | if(pI2C2) 89 | pI2C2->DmaTxIRQ(); 90 | #endif 91 | #endif 92 | } 93 | 94 | 95 | 96 | 97 | /////////////////////////////// 98 | ///I2C2 DMA receive channel 99 | ////////////////////////////// 100 | void DMA1_Channel5_IRQHandler() 101 | { 102 | #ifdef USE_I2C 103 | #ifdef I2C_USE_DMA 104 | if(pI2C2) 105 | pI2C2->DmaRxIRQ(); 106 | #endif 107 | #endif 108 | } 109 | 110 | 111 | 112 | /////////////////////////////// 113 | ///I2C1 DMA send channel 114 | ////////////////////////////// 115 | void DMA1_Channel6_IRQHandler() 116 | { 117 | #ifdef USE_I2C 118 | #ifdef I2C_USE_DMA 119 | if(pI2C1) 120 | pI2C1->DmaTxIRQ(); 121 | #endif 122 | #endif 123 | } 124 | 125 | 126 | ///////////////////////////////// 127 | ///USART2 DMA send channel 128 | ///I2C1 DMA receive channel 129 | //////////////////////////////// 130 | void DMA1_Channel7_IRQHandler() 131 | { 132 | #ifdef USE_USART 133 | if(pUSART2) 134 | pUSART2->DmaIrq(); 135 | #endif 136 | 137 | #ifdef USE_I2C 138 | #ifdef I2C_USE_DMA 139 | if(pI2C1) 140 | pI2C1->DmaRxIRQ(); 141 | #endif 142 | #endif 143 | } 144 | 145 | 146 | /*****************************************DMA INTERRUPT END**************************************/ 147 | 148 | /*****************************************SPI INTERRUPT**************************************/ 149 | #ifdef USE_SPI 150 | SPI *pSPI1 = 0; 151 | SPI *pSPI2 = 0; 152 | 153 | void SPI1_IRQHandler(void){ 154 | if(pSPI1) 155 | pSPI1->SpiIrq(); 156 | } 157 | 158 | void SPI2_IRQHandler(void){ 159 | if(pSPI2) 160 | pSPI2->SpiIrq(); 161 | } 162 | #endif 163 | /*****************************************SPI INTERRUPT END**************************************/ 164 | 165 | /*****************************************EXTI INTERRUPT START****************************/ 166 | 167 | #ifdef USE_NRF_IRQ 168 | NRF24L01 *pNRF = 0; 169 | 170 | void EXTI2_IRQHandler(void){ 171 | pNRF->IRQIrq(); 172 | } 173 | 174 | #endif 175 | 176 | /*****************************************EXTI INTERRUPT END****************************/ 177 | 178 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/Interrupt.h: -------------------------------------------------------------------------------- 1 | /** 2 | *@file Interrupt.h 3 | *@date 2015-10-27 4 | *@author 5 | *@breif interrupt management file 6 | * 7 | */ 8 | 9 | #ifndef __INTERRUPT_H 10 | #define __INTERRUPT_H 11 | 12 | /***************************************configuration********************************************/ 13 | #define USE_USART 14 | #define USE_I2C 15 | #define USE_SPI 16 | #define USE_NRF_IRQ 17 | /************************************configuration end********************************************/ 18 | 19 | #ifdef USE_NRF_IRQ 20 | #include "NRF24L01.h" 21 | extern NRF24L01 *pNRF; 22 | extern "C"{ 23 | void EXTI2_IRQHandler(void); 24 | } 25 | #endif 26 | 27 | #ifdef USE_USART 28 | #include "USART.h" 29 | extern USART *pUSART1; 30 | extern USART *pUSART2; 31 | extern USART *pUSART3; 32 | extern "C"{ 33 | void USART1_IRQHandler(void); 34 | void USART2_IRQHandler(void); 35 | void USART3_IRQHandler(void); 36 | 37 | } 38 | #endif 39 | 40 | #ifdef USE_I2C 41 | #include "I2C.h" 42 | extern I2C *pI2C1; 43 | extern I2C *pI2C2; 44 | extern "C"{ 45 | void I2C1_EV_IRQHandler(void); 46 | void I2C2_EV_IRQHandler(void); 47 | void I2C1_ER_IRQHandler(void); 48 | void I2C2_ER_IRQHandler(void); 49 | } 50 | #endif 51 | 52 | #ifdef USE_SPI 53 | #include "SPI.h" 54 | extern SPI *pSPI1; 55 | extern SPI *pSPI2; 56 | extern "C"{ 57 | void SPI1_IRQHandler(void); 58 | void SPI2_IRQHandler(void); 59 | } 60 | #endif 61 | 62 | extern "C"{ 63 | ////////////////////////////////// 64 | ///USART3 send channel 65 | ////////////////////////////////// 66 | void DMA1_Channel2_IRQHandler(); 67 | ///////////////////////////////// 68 | ///USART1 DMA send channel 69 | ///I2C2 DMA send channel 70 | ///////////////////////////////// 71 | void DMA1_Channel4_IRQHandler(); 72 | /////////////////////////////// 73 | ///I2C2 DMA receive channel 74 | ////////////////////////////// 75 | void DMA1_Channel5_IRQHandler(); 76 | 77 | /////////////////////////////// 78 | ///I2C1 DMA send channel 79 | ////////////////////////////// 80 | void DMA1_Channel6_IRQHandler(); 81 | 82 | ///////////////////////////////// 83 | ///USART2 DMA send channel 84 | ///I2C1 DMA receive channel 85 | //////////////////////////////// 86 | void DMA1_Channel7_IRQHandler(); 87 | } 88 | 89 | #endif 90 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/LED.cpp: -------------------------------------------------------------------------------- 1 | #include "LED.h" 2 | 3 | 4 | ///构造函数 5 | ///@param gpio GPIO类对象,分配片上资源 6 | ///@param highLevelOn 是否输出高电平时为LED打开 7 | ///////////////////////// 8 | LED::LED(GPIO &gpio,bool highLevelOn) 9 | :mGPIO(gpio) 10 | { 11 | if(highLevelOn) 12 | mLevelOn=1; 13 | else 14 | mLevelOn=0; 15 | } 16 | 17 | 18 | //////////////////////// 19 | ///翻转(开-->关 , 关-->开) 20 | /////////////////////// 21 | void LED::Toggle() 22 | { 23 | if(mGPIO.GetLevel()) 24 | mGPIO.SetLevel(0); 25 | else 26 | mGPIO.SetLevel(1); 27 | } 28 | 29 | ////////////////////// 30 | ///打开LED 31 | ///////////////////// 32 | void LED::On() 33 | { 34 | mGPIO.SetLevel(mLevelOn); 35 | } 36 | 37 | ///////////////////// 38 | ///关闭LED 39 | //////////////////// 40 | void LED::Off() 41 | { 42 | mGPIO.SetLevel(mLevelOn^1); 43 | } 44 | 45 | //////////////////////// 46 | ///闪烁n次 47 | ///@param time 闪烁次数 48 | ///@param Interval 闪烁间隔 (ms) 49 | /////////////////////// 50 | void LED::Blink(uint8_t time,uint16_t interval) 51 | { 52 | for(uint8_t i=0;i关 , 关-->开) 19 | /////////////////////// 20 | void Toggle(); 21 | 22 | ////////////////////// 23 | ///打开LED 24 | ///////////////////// 25 | void On(); 26 | 27 | ///////////////////// 28 | ///关闭LED 29 | //////////////////// 30 | void Off(); 31 | 32 | //////////////////////// 33 | ///闪烁n次 34 | ///@param time 闪烁次数 35 | ///@param Interval 闪烁间隔(ms) 36 | /////////////////////// 37 | void Blink(uint8_t time,uint16_t interval); 38 | 39 | //////////////////////// 40 | ///两个灯一起闪烁n次 41 | ///@param 另一个灯的引用 42 | ///@param time 闪烁次数 43 | ///@param Interval 闪烁间隔(ms) 44 | /////////////////////// 45 | void Blink2(LED &led,uint8_t time,uint16_t interval); 46 | 47 | 48 | //////////////////////// 49 | ///两个灯交替闪烁n次 50 | ///@param 另一个灯的引用 51 | ///@param time 闪烁次数 52 | ///@param Interval 闪烁间隔(ms) 53 | /////////////////////// 54 | void Blink3(LED &led,uint8_t time,uint16_t interval); 55 | 56 | private: 57 | ////////////////////////// 58 | ///GPIO的类的实例对象引用 59 | ////////////////////////// 60 | GPIO & mGPIO; 61 | //////////////////////// 62 | ///标志开启LED时取的电平高低 63 | //////////////////////// 64 | unsigned char mLevelOn; 65 | 66 | 67 | 68 | }; 69 | 70 | 71 | #endif 72 | 73 | 74 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/NRF24L01.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/NRF24L01.cpp -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/NRF24L01.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/NRF24L01.h -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/SPI.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/SPI.cpp -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/SPI.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/SPI.h -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/TaskManager.cpp: -------------------------------------------------------------------------------- 1 | #include "TaskManager.h" 2 | 3 | TaskManager tskmgr; 4 | 5 | double TaskManager::_it_time = 0; 6 | double TaskManager::_new_time = 0; 7 | double TaskManager::_old_time = 0; 8 | 9 | //Constructor 10 | TaskManager::TaskManager() 11 | { 12 | SysTick->CTRL &= 0xFFFFFFFB; //Clock div 8 = 9M 13 | SysTick->LOAD = 16200000; //1.8s 14 | SysTick->CTRL |= 0x00000003; //INT +ENABLE 15 | } 16 | //get current time since power on 17 | double TaskManager::Time(void) 18 | { 19 | _new_time = _it_time + 1.8 - SysTick->VAL/9000000.0; //update current time 20 | 21 | if(_new_time - _old_time > 1.799) //check if breaked by SysTick interrupt 22 | { 23 | _new_time -= 1.8; //calibrate current time 24 | } 25 | _old_time = _new_time; //update old time 26 | return _new_time; 27 | } 28 | 29 | //微秒延时 30 | void TaskManager::DelayUs(u16 nus) 31 | { 32 | double OldT=Time(); 33 | while((Time()-OldT)=timeout) 53 | { 54 | record = Time(); //更新记录 55 | return true; 56 | } 57 | else 58 | return false; 59 | } 60 | 61 | 62 | //SysTick interrupt IRQ handler 63 | extern "C" 64 | { 65 | void SysTick_Handler(void) 66 | { 67 | TaskManager::_it_time += 1.8; 68 | } 69 | } 70 | 71 | 72 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/TaskManager.h: -------------------------------------------------------------------------------- 1 | #ifndef _TASK_MANAGER_H_ 2 | #define _TASK_MANAGER_H_ 3 | #include "stm32f10x.h" 4 | 5 | class TaskManager 6 | { 7 | private: 8 | static double _new_time; //current updated time 9 | static double _old_time; //last updated time 10 | public: 11 | static double _it_time; //time = SysTick interrupt counter*1.8s 12 | public: 13 | TaskManager(); //constructor 14 | static double Time(void); //get current time 15 | static void DelayUs(u16 nus); 16 | static void DelayMs(u16 nms); 17 | static void DelayS(u16 ns); 18 | bool TimeSlice(double &record,double timeout); //传入一个时间记录值和一个超时时间 记录达到了超时时间返回tree 19 | }; 20 | extern TaskManager tskmgr; 21 | 22 | #define MOD_ERROR 0x00 23 | #define MOD_READY 0x01 24 | #define MOD_BUSY 0x02 25 | #define MOD_LOCK 0x04 26 | #define MOD_UNLOCK 0x08 27 | 28 | 29 | #endif 30 | -------------------------------------------------------------------------------- /libraries/OffChip/NRF24L01/两机通讯(中断)/test(发送)/lib/Vector3.h: -------------------------------------------------------------------------------- 1 | #ifndef _VECTOR3_H_ 2 | #define _VECTOR3_H_ 3 | 4 | #include "math.h" 5 | 6 | template 7 | class Vector3 8 | { 9 | public: 10 | T x,y,z; 11 | public: 12 | //defualt constructor 13 | Vector3() { x = 0; y = 0; z = 0; } 14 | // setting ctor 15 | Vector3(T x0, T y0, T z0) : x(x0), y(y0), z(z0) {} 16 | //"()" overload 17 | void operator()(T x0, T y0, T z0){x= x0; y= y0; z= z0;} 18 | //"==" overload 19 | bool operator==(const Vector3 &v){return (x==v.x && y==v.y && z==v.z); } 20 | //"!=" overload 21 | bool operator!=(const Vector3 &v){return (x!=v.x || y!=v.y || z!=v.z); } 22 | // "-" negation overload 23 | Vector3 operator-(void) const { return Vector3(-x,-y,-z);} 24 | //"+" addition overload 25 | Vector3 operator+(const Vector3 &v) const { return Vector3(x+v.x, y+v.y, z+v.z); } 26 | //"-" subtraction overload 27 | Vector3 operator-(const Vector3 &v) const { return Vector3(x-v.x, y-v.y, z-v.z); } 28 | //"*" multiply overload 29 | Vector3 operator*(const T n)const { return Vector3(x*n, y*n, z*n); } 30 | //"/" divsion overload 31 | Vector3 operator/(const T n)const { return Vector3(x/n, y/n, z/n); } 32 | //"=" 33 | Vector3 &operator=(const Vector3 &v){x=v.x; y=v.y; z=v.z; return *this;} 34 | //"+=" overload 35 | Vector3 &operator+=(const Vector3 &v) { x+=v.x; y+=v.y; z+=v.z; return *this; } 36 | //"-=" overload 37 | Vector3 &operator-=(const Vector3 &v) { x-=v.x; y-=v.y; z-=v.z; return *this; } 38 | //"*=" overload 39 | Vector3 &operator*=(const T n) { x*=n; y*=n; z*=n; return *this; } 40 | // uniform scaling 41 | Vector3 &operator/=(const T n) { x/=n; y/=n; z/=n; return *this; } 42 | //dot product 43 | T operator*(const Vector3 &v) const { return x*v.x + y*v.y + z*v.z; } 44 | //cross product 45 | Vector3 operator %(const Vector3 &v)const { return Vector3(y*v.z-z*v.y, z*v.x-x*v.z, x*v.y-y*v.x);} 46 | // gets the length of this vector squared 47 | T LengthSquared() const { return (T)(*this * *this); } 48 | // gets the length of this vector 49 | float Length(void) const { return (T)sqrt(*this * *this); } 50 | // normalizes this vector 51 | void Normalize() { *this/=Length(); } 52 | // zero the vector 53 | void Zero() { x = y = z = 0.0; } 54 | // returns the normalized version of this vector 55 | Vector3 Normalized() const { return *this/Length(); } 56 | // check if any elements are NAN 57 | bool IsNan(void) { return isnan(x) || isnan(y) || isnan(z); } 58 | // check if any elements are infinity 59 | bool IsInf(void) { return isinf(x) || isinf(y) || isinf(z); } 60 | 61 | }; 62 | typedef Vector3 Vector3f; 63 | #endif // VECTOR3_H 64 | -------------------------------------------------------------------------------- /libraries/OffChip/Print/DPPrint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/Print/DPPrint.cpp -------------------------------------------------------------------------------- /libraries/OffChip/Print/DPPrint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/Print/DPPrint.h -------------------------------------------------------------------------------- /libraries/OffChip/Remoter/Remoter.h: -------------------------------------------------------------------------------- 1 | #ifndef _REMOTER_H_ 2 | #define _REMOTER_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "TaskManager.h" 6 | 7 | class Remoter 8 | { 9 | protected: 10 | float mRawT[10]; 11 | float mMaxT[10]; //the max duration(ms) of channel x 12 | float mMinT[10]; //the min duration(ms) of channel x 13 | bool mLocked; //true: remoter is locked, false: unlocked 14 | bool mCalibrating;//true: currently calibrate rc, false: not calibrate rc 15 | float mLockVal[4]; 16 | float mUnlockVal[4]; 17 | u8 mRCState; 18 | public: 19 | Remoter() //Constructor 20 | { 21 | for(u8 i=0;i<10;i++) 22 | { 23 | mMaxT[i] = 1.9f; 24 | mMinT[i] = 1.1f; 25 | } 26 | mLocked = true; 27 | mCalibrating = false; 28 | mRCState = MOD_ERROR; 29 | mLockVal[0] = 0; 30 | mLockVal[1] = 0; 31 | mLockVal[2] = 0; 32 | mLockVal[3] = 0; 33 | mUnlockVal[0] = 100; 34 | mUnlockVal[1] = 0; 35 | mUnlockVal[2] = 0; 36 | mUnlockVal[3] = 0; 37 | } 38 | virtual float operator[](u8 chNum) = 0; //return the percentage of channel x (0.0 ~ 100.0), the same as Channel 39 | virtual float Channel(u8 chNum) = 0; //return the percentage of channel x (0.0 ~ 100.0), the same as operator[] 40 | virtual float ChannelRaw(u8 chNum) = 0; //return the raw value of channel x (ms) 41 | virtual u8 Update() = 0; 42 | bool IsLocked() { return mLocked;} //return the locked status of remoter 43 | void SetLockState(float roll, float pitch, float yaw, float throttle) 44 | { 45 | mLockVal[0] = roll; 46 | mLockVal[1] = pitch; 47 | mLockVal[2] = yaw; 48 | mLockVal[3] = throttle; 49 | } 50 | void SetUnlockState(float roll, float pitch, float yaw, float throttle) 51 | { 52 | mUnlockVal[0] = roll; 53 | mUnlockVal[1] = pitch; 54 | mUnlockVal[2] = yaw; 55 | mUnlockVal[3] = throttle; 56 | } 57 | void StartCalibrate() 58 | { 59 | if(Ready() && Locked()) 60 | { 61 | mRCState = (MOD_READY | MOD_ADJUST); 62 | for(u8 i=0;i<10;i++) 63 | { 64 | mMaxT[i] = 1.5f; 65 | mMinT[i] = 1.5f; 66 | } 67 | } 68 | } 69 | void StopCalibrate() 70 | { 71 | if(Ready() && Calibrating()) 72 | { 73 | mRCState = (MOD_READY | MOD_LOCK); 74 | } 75 | } 76 | bool Ready() 77 | { 78 | if(mRCState & MOD_READY) 79 | return true; 80 | else 81 | return false; 82 | } 83 | bool UnLocked() 84 | { 85 | if(mRCState & MOD_UNLOCK) 86 | return true; 87 | else 88 | return false; 89 | } 90 | bool Locked() 91 | { 92 | if(mRCState & MOD_LOCK) 93 | return true; 94 | else 95 | return false; 96 | } 97 | bool Calibrating() 98 | { 99 | if(mRCState & MOD_ADJUST) 100 | return true; 101 | else 102 | return false; 103 | } 104 | float Roll() { return Channel(1); } 105 | float Pitch() { return Channel(2); } 106 | float Yaw() { return Channel(3); } 107 | float Throttle() { return Channel(4); } 108 | float Mode() { return Channel(5); } 109 | }; 110 | 111 | 112 | #endif 113 | 114 | 115 | 116 | -------------------------------------------------------------------------------- /libraries/OffChip/Remoter/Remoter_PWM_EXIT.cpp: -------------------------------------------------------------------------------- 1 | #include "Remoter_PWM_EXIT.h" 2 | #include "math.h" 3 | 4 | 5 | Remoter_PWM_EXIT::Remoter_PWM_EXIT(InputCapture_EXIT *icpRoll, 6 | InputCapture_EXIT *icpPitch, //pitch ICP 7 | InputCapture_EXIT *icpYaw, //yaw ICP 8 | InputCapture_EXIT *icpThrottle, //throttle 9 | InputCapture_EXIT *icpMode, //Mode ICP 10 | InputCapture_EXIT *icpAux1, //Auxiliary 1 ICP 11 | InputCapture_EXIT *icpAux2, //Auxiliary 2 ICP 12 | InputCapture_EXIT *icpAux3, //Auxiliary 3 ICP 13 | InputCapture_EXIT *icpAux4, //Auxiliary 4 ICP 14 | InputCapture_EXIT *icpAux5 //Auxiliary 5 ICP 15 | ) 16 | { 17 | mICP[0] = icpRoll; 18 | mICP[1] = icpPitch; 19 | mICP[2] = icpYaw; 20 | mICP[3] = icpThrottle; 21 | mICP[4] = icpMode; 22 | mICP[5] = icpAux1; 23 | mICP[6] = icpAux2; 24 | mICP[7] = icpAux3; 25 | mICP[8] = icpAux4; 26 | mICP[9] = icpAux5; 27 | } 28 | 29 | float Remoter_PWM_EXIT::operator[](u8 chNum) 30 | { 31 | chNum -= 1; 32 | if(mICP[chNum]) 33 | { 34 | double chVal = mRawT[chNum]; 35 | chVal = (chVal-mMinT[chNum])/(mMaxT[chNum]-mMinT[chNum]); 36 | if(chVal>1.0) chVal = 1.0; 37 | if(chVal<0.0) chVal = 0.0; 38 | return chVal*100; 39 | } 40 | return 0; 41 | } 42 | 43 | float Remoter_PWM_EXIT::Channel(u8 chNum) 44 | { 45 | chNum -= 1; 46 | if(mICP[chNum]) 47 | { 48 | float chVal = mRawT[chNum]; 49 | chVal = (chVal-mMinT[chNum])/(mMaxT[chNum]-mMinT[chNum]); 50 | if(chVal>1.0f) chVal = 1.0f; 51 | if(chVal<0.0f) chVal = 0.0f; 52 | return chVal*100; 53 | } 54 | return 0; 55 | } 56 | 57 | float Remoter_PWM_EXIT::ChannelRaw(u8 chNum) 58 | { 59 | return mRawT[--chNum]; 60 | } 61 | 62 | 63 | u8 Remoter_PWM_EXIT::Update() 64 | { 65 | static double newTime = 0, oldTime = 0, interval = 0, lockTime = 0, unlockTime = 0; 66 | static u8 rcDelayCnt = 0; //when power on, rc is not stable, should delay for a while 67 | //check if need reset max and min value of all channels 68 | newTime = tskmgr.Time(); //get current time 69 | interval = newTime - oldTime; 70 | if(interval<0.02) 71 | { 72 | return MOD_BUSY; 73 | } 74 | 75 | oldTime = newTime; //update old time 76 | 77 | if(rcDelayCnt<100) rcDelayCnt++; 78 | 79 | //update all channel values 80 | for(u8 i=0; i<10; i++) 81 | { 82 | if(mICP[i]) 83 | { 84 | mRawT[i] = mICP[i]->Value(); //get channel value 85 | 86 | 87 | if(mRawT[i]<0.9f || mRawT[i]>2.1f) //wrong channel data 88 | { 89 | mRCState = MOD_ERROR; //error 90 | return MOD_ERROR; 91 | } 92 | 93 | if(Ready() && Calibrating()) //curent calibrating 94 | { 95 | if(rcDelayCnt>90) 96 | { 97 | if(mRawT[i]>mMaxT[i]) mMaxT[i] = mRawT[i]; //update max value 98 | if(mRawT[i]5) 113 | mRCState = (MOD_READY | MOD_UNLOCK); 114 | lockTime = 0; 115 | } 116 | else if(Ready() && UnLocked()) //current unlocked, check lock event 117 | { 118 | if(abs(Channel(4)-mLockVal[3])<1) 119 | lockTime += interval; 120 | else 121 | lockTime = 0; 122 | if(lockTime>4) 123 | mRCState = (MOD_READY | MOD_UNLOCK); 124 | unlockTime = 0; 125 | } 126 | return mRCState; 127 | } 128 | 129 | -------------------------------------------------------------------------------- /libraries/OffChip/Remoter/Remoter_PWM_EXIT.h: -------------------------------------------------------------------------------- 1 | #ifndef _REMOTER_PWM_EXIT_H_ 2 | #define _REMOTER_PWM_EXIT_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "Remoter.h" 6 | #include "InputCapture_EXIT.h" 7 | 8 | 9 | class Remoter_PWM_EXIT: public Remoter 10 | { 11 | private: 12 | InputCapture_EXIT *mICP[10]; 13 | public: 14 | Remoter_PWM_EXIT(InputCapture_EXIT *icpRoll, //roll ICP 15 | InputCapture_EXIT *icpPitch, //pitch ICP 16 | InputCapture_EXIT *icpYaw = 0, //yaw ICP 17 | InputCapture_EXIT *icpThrottle = 0, //throttle 18 | InputCapture_EXIT *icpMode = 0, //Mode ICP 19 | InputCapture_EXIT *icpAux1 = 0, //Auxiliary 1 ICP 20 | InputCapture_EXIT *icpAux2 = 0, //Auxiliary 2 ICP 21 | InputCapture_EXIT *icpAux3 = 0, //Auxiliary 3 ICP 22 | InputCapture_EXIT *icpAux4 = 0, //Auxiliary 4 ICP 23 | InputCapture_EXIT *icpAux5 = 0 //Auxiliary 5 ICP 24 | ); 25 | virtual float operator[](u8 chNum); //return the percentage of channel x (0.0 ~ 100.0) 26 | virtual float Channel(u8 chNum); //return the percentage of channel x (0.0 ~ 100.0), the same as operator[] 27 | virtual float ChannelRaw(u8 chNum); //return the raw value of channel x (ms) 28 | virtual u8 Update(); //update rc data, return rc status, check lock / unlock 29 | }; 30 | 31 | #endif 32 | 33 | 34 | -------------------------------------------------------------------------------- /libraries/OffChip/Remoter/Remoter_PWM_TIM.cpp: -------------------------------------------------------------------------------- 1 | #include "Remoter_PWM_TIM.h" 2 | #include "math.h" 3 | 4 | 5 | Remoter_PWM_TIM::Remoter_PWM_TIM(InputCapture_TIM *icpRoll, u8 chRoll, InputCapture_TIM *icpPitch, u8 chPitch, 6 | InputCapture_TIM *icpYaw, u8 chYaw, InputCapture_TIM *icpThrottle, u8 chThrottle, 7 | InputCapture_TIM *icpMode, u8 chMode, InputCapture_TIM *icpAux1, u8 chAux1, 8 | InputCapture_TIM *icpAux2, u8 chAux2, InputCapture_TIM *icpAux3, u8 chAux3, 9 | InputCapture_TIM *icpAux4, u8 chAux4, InputCapture_TIM *icpAux5, u8 chAux5 ) 10 | { 11 | mICP[0] = icpRoll; mChNum[0] = chRoll; 12 | mICP[1] = icpPitch; mChNum[1] = chPitch; 13 | mICP[2] = icpYaw; mChNum[2] = chYaw; 14 | mICP[3] = icpThrottle; mChNum[3] = chThrottle; 15 | mICP[4] = icpMode; mChNum[4] = chMode; 16 | mICP[5] = icpAux1; mChNum[5] = chAux1; 17 | mICP[6] = icpAux2; mChNum[6] = chAux2; 18 | mICP[7] = icpAux3; mChNum[7] = chAux3; 19 | mICP[8] = icpAux4; mChNum[8] = chAux4; 20 | mICP[9] = icpAux5; mChNum[9] = chAux5; 21 | } 22 | 23 | float Remoter_PWM_TIM::operator[](u8 chNum) 24 | { 25 | chNum -= 1; 26 | if(mICP[chNum] && mChNum[chNum]) 27 | { 28 | float chVal = mRawT[chNum]; 29 | chVal = (chVal-mMinT[chNum])/(mMaxT[chNum]-mMinT[chNum]); 30 | if(chVal>1.0f) chVal = 1.0f; 31 | if(chVal<0.0f) chVal = 0.0f; 32 | return chVal*100; 33 | } 34 | return 0; 35 | } 36 | 37 | float Remoter_PWM_TIM::Channel(u8 chNum) 38 | { 39 | chNum -= 1; 40 | if(mICP[chNum] && mChNum[chNum]) 41 | { 42 | float chVal = mRawT[chNum]; 43 | chVal = (chVal-mMinT[chNum])/(mMaxT[chNum]-mMinT[chNum]); 44 | if(chVal>1.0f) chVal = 1.0f; 45 | if(chVal<0.0f) chVal = 0.0f; 46 | return chVal*100; 47 | } 48 | return 0; 49 | } 50 | 51 | float Remoter_PWM_TIM::ChannelRaw(u8 chNum) 52 | { 53 | return mRawT[--chNum]; 54 | } 55 | 56 | 57 | u8 Remoter_PWM_TIM::Update() 58 | { 59 | static double newTime = 0, oldTime = 0, interval = 0, lockTime = 0, unlockTime = 0; 60 | static u8 rcDelayCnt = 0; //when power on, rc is not stable, should delay for a while 61 | //check if need reset max and min value of all channels 62 | newTime = tskmgr.Time(); //get current time 63 | interval = newTime - oldTime; 64 | if(interval<0.02) { 65 | return MOD_BUSY; 66 | } 67 | 68 | oldTime = newTime; //update old time 69 | 70 | if(rcDelayCnt<100) rcDelayCnt++; 71 | 72 | //update all channel values 73 | for(u8 i=0; i<10; i++) 74 | { 75 | if(mICP[i] && mChNum[i]) 76 | { 77 | mRawT[i] = (*mICP[i])[mChNum[i]]; //get channel value 78 | if(mLocked && mCalibrating) 79 | { 80 | if(rcDelayCnt>90) 81 | { 82 | if(mRawT[i]>mMaxT[i]) mMaxT[i] = mRawT[i]; //update max value 83 | if(mRawT[i]5) 97 | mLocked = false; 98 | lockTime = 0; 99 | return MOD_READY | MOD_LOCK; 100 | } 101 | else 102 | { 103 | if(abs(Channel(4)-mLockVal[3])<1) 104 | lockTime += interval; 105 | else 106 | lockTime = 0; 107 | if(lockTime>4) 108 | mLocked = true; 109 | unlockTime = 0; 110 | return MOD_READY | MOD_UNLOCK; 111 | } 112 | } 113 | 114 | bool Remoter_PWM_TIM::getHealth(){ 115 | return _health; 116 | } 117 | 118 | -------------------------------------------------------------------------------- /libraries/OffChip/Remoter/Remoter_PWM_TIM.h: -------------------------------------------------------------------------------- 1 | #ifndef _REMOTER_PWM_H_ 2 | #define _REMOTER_PWM_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "Remoter.h" 6 | #include "InputCapture_TIM.h" 7 | 8 | 9 | class Remoter_PWM_TIM: public Remoter 10 | { 11 | private: 12 | InputCapture_TIM *mICP[10]; 13 | u8 mChNum[10]; 14 | bool _health; 15 | public: 16 | Remoter_PWM_TIM(InputCapture_TIM *icpRoll, u8 chRoll, //roll ICP and channel number in ICP 17 | InputCapture_TIM *icpPitch, u8 chPitch, //pitch ICP and channel number in ICP 18 | InputCapture_TIM *icpYaw = 0, u8 chYaw = 0, //yaw ICP and channel number in ICP 19 | InputCapture_TIM *icpThrottle = 0, u8 chThrottle = 0, //throttle ICP and channel number in ICP 20 | InputCapture_TIM *icpMode = 0, u8 chMode = 0, //Mode ICP and channel number in ICP 21 | InputCapture_TIM *icpAux1 = 0, u8 chAux1 = 0, //Auxiliary 1 ICP and channel number in ICP 22 | InputCapture_TIM *icpAux2 = 0, u8 chAux2 = 0, //Auxiliary 2 ICP and channel number in ICP 23 | InputCapture_TIM *icpAux3 = 0, u8 chAux3 = 0, //Auxiliary 3 ICP and channel number in ICP 24 | InputCapture_TIM *icpAux4 = 0, u8 chAux4 = 0, //Auxiliary 4 ICP and channel number in ICP 25 | InputCapture_TIM *icpAux5 = 0, u8 chAux5 = 0 //Auxiliary 5 ICP and channel number in ICP 26 | ); 27 | virtual float operator[](u8 chNum); //return the percentage of channel x (0.0 ~ 100.0) 28 | virtual float Channel(u8 chNum); //return the percentage of channel x (0.0 ~ 100.0), the same as operator[] 29 | virtual float ChannelRaw(u8 chNum); //return the raw value of channel x (ms) 30 | virtual u8 Update(); //update rc data, return rc status, check lock / unlock 31 | bool getHealth(); 32 | }; 33 | 34 | #endif 35 | 36 | 37 | -------------------------------------------------------------------------------- /libraries/OffChip/SHARP_1014_PM2_5/SHARP_1014_PM2_5.cpp: -------------------------------------------------------------------------------- 1 | #include "SHARP_1014_PM2_5.h" 2 | 3 | /*---------------------------TEST----------------------------------*/ 4 | sharp_1014_pm2_5::sharp_1014_pm2_5(GPIO &LED):mLed(LED) 5 | { 6 | OriginalVol=0; 7 | AdcOriginalVol=0; 8 | ADC_init(); 9 | 10 | } 11 | 12 | float sharp_1014_pm2_5::testGetVol() 13 | { 14 | //延时测试方案: 管脚拉低,延时280us,读取AD,延时40us,拉高管脚,再延时9680 us。 15 | mLed.SetLevel(0); 16 | tskmgr.DelayUs(280); 17 | tskmgr.DelayUs(40); 18 | mLed.SetLevel(1); 19 | tskmgr.DelayUs(9680); 20 | 21 | return OriginalVol; 22 | } 23 | 24 | 25 | 26 | //sharp_1014_pm2_5::sharp_1014_pm2_5(PWM &Led,ADC &Adc,u8 AdcCh):mLED(Led),mAdc(Adc) 27 | //{ 28 | // OriginalVol=0; 29 | // AdcChannel = AdcCh; 30 | //} 31 | 32 | 33 | bool sharp_1014_pm2_5::updata()//数据更新,最快更新时间:10ms一次 34 | { 35 | mLed.SetLevel(0); 36 | tskmgr.DelayUs(280); 37 | AdcOriginalVol = Get_ADC(); 38 | tskmgr.DelayUs(40); 39 | mLed.SetLevel(1); 40 | tskmgr.DelayUs(9680); 41 | return true; 42 | } 43 | 44 | float sharp_1014_pm2_5::getOriginalVol(float NearVccR,float OtherR)//读取原始电压值,该值根据分压电阻决定 45 | { 46 | 47 | OriginalVol= (float)AdcOriginalVol*0.0008056640625; //将原始值转化为电压 48 | OriginalVol=OriginalVol*(NearVccR/OtherR+1);//由于使用了8.61:14.84的电阻分压,所以要转化为原始电压 49 | return OriginalVol; 50 | } 51 | 52 | 53 | float sharp_1014_pm2_5::InVolOutDensity(float Vol) 54 | { 55 | float a = 0.17; 56 | float b = -0.1; 57 | //由图得出一个一元二次方程 58 | return (a*Vol+b); 59 | 60 | } 61 | 62 | bool sharp_1014_pm2_5::ADC_init() 63 | { 64 | //时钟初始化 65 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_ADC1,ENABLE); 66 | RCC_ADCCLKConfig(RCC_PCLK2_Div6); 67 | 68 | //管脚初始化 69 | GPIO_InitTypeDef GPIO_InitStructure; 70 | GPIO_InitStructure.GPIO_Pin = ADC_PIN; 71 | GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN; 72 | GPIO_Init(ADC_GPIO,&GPIO_InitStructure); 73 | //ADC初始化 74 | ADC_DeInit(ADC1); 75 | ADC_InitTypeDef ADC_init; 76 | ADC_init.ADC_Mode = ADC_Mode_Independent; //独立工作模式 77 | ADC_init.ADC_ScanConvMode = DISABLE; //单通道模式 78 | ADC_init.ADC_ContinuousConvMode = DISABLE; //单次转换模式 79 | ADC_init.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None ;//软件触发 80 | ADC_init.ADC_DataAlign = ADC_DataAlign_Right; //右对齐 81 | ADC_init.ADC_NbrOfChannel = 1;//1个通道 82 | ADC_Init(ADC1,&ADC_init); 83 | //设置ADC的一些通道规则 84 | ADC_Cmd(ADC1,ENABLE); 85 | 86 | // 87 | ADC_ResetCalibration(ADC1); 88 | while(ADC_GetResetCalibrationStatus(ADC1)); 89 | ADC_StartCalibration(ADC1); 90 | while(ADC_GetCalibrationStatus(ADC1)); 91 | return true; 92 | 93 | } 94 | 95 | uint16_t sharp_1014_pm2_5::Get_ADC() 96 | { 97 | ADC_RegularChannelConfig(ADC1,ADC_Channel_2,1,ADC_SampleTime_55Cycles5); 98 | ADC_SoftwareStartConvCmd(ADC1,ENABLE);//启动转换等待转换完成 99 | while(!ADC_GetFlagStatus(ADC1,ADC_FLAG_EOC)); 100 | return (uint16_t)ADC_GetConversionValue(ADC1); 101 | } 102 | 103 | -------------------------------------------------------------------------------- /libraries/OffChip/SHARP_1014_PM2_5/SHARP_1014_PM2_5.h: -------------------------------------------------------------------------------- 1 | /* 2 | 夏普GP2Y1014 6823 PM2.5粉尘传感器,驱动方式主要用一路PWM(周期10ms,启动时间0.32ms)来控制LED灯 3 | 然后才能从AD角读出电压值。 4 | 有传感器结构图可以看出控制LED的是一个PNP三极管,所以当电平为低的时候导通,开启。 5 | 原定计划是用PWM,然后再中断时间中启动ADC读取,但先使用延时的方式测试传感器 6 | 7 | */ 8 | 9 | 10 | 11 | #ifndef _SHARP_1014_PM2_5_H 12 | #define _SHARP_1014_PM2_5_H 13 | 14 | #include "stm32f10x.h" 15 | #include "GPIO.h" 16 | #include "TaskManager.h" 17 | 18 | //暂时先用宏定义 19 | #define ADC_PIN GPIO_Pin_2 20 | #define ADC_GPIO GPIOA 21 | #define ADC_CHANNEL ADC_Channel_2 22 | 23 | class sharp_1014_pm2_5{ 24 | private: 25 | 26 | uint16_t AdcOriginalVol;//保存ADC寄存器的原始值 27 | float OriginalVol;//保存计算出的电压值 28 | GPIO &mLed; 29 | 30 | bool ADC_init(); 31 | uint16_t Get_ADC(); 32 | float InVolOutDensity(float Vol); 33 | 34 | public: 35 | sharp_1014_pm2_5(GPIO &LED); 36 | float testGetVol(); 37 | bool updata();//数据更新,最快更新时间:10ms一次 38 | float getOriginalVol(float NearVccR,float OtherR);//读取原始电压值,该值根据分压电阻决定 39 | 40 | }; 41 | 42 | 43 | 44 | #endif 45 | 46 | -------------------------------------------------------------------------------- /libraries/OffChip/SHARP_1051_PM2_5/SHARP_PM2_5.cpp: -------------------------------------------------------------------------------- 1 | #include "SHARP_PM2_5.h" 2 | 3 | Sharp_PM_2_5::Sharp_PM_2_5(USART &com):mCom(com) 4 | {} 5 | 6 | bool Sharp_PM_2_5::Update() 7 | { 8 | //u8 buffer[70]; //buffer 最大70 9 | u8 data[5]; 10 | float temp; 11 | u8 ch; 12 | int num=mCom.RxSize(); 13 | if(num > 7) 14 | { 15 | mCom.GetBytes(&ch,1); 16 | if(ch!=0xaa) 17 | return false; 18 | else 19 | mCom.GetBytes(data,5); 20 | if(Check(data,4,data[4]))//校验 21 | { 22 | temp=(float)(data[0]*256+data[1])/1024*5; 23 | UD=temp * COEFFICIENT_A; 24 | mCom.ClearRxBuf(); 25 | return true; 26 | } 27 | else 28 | return false; 29 | } 30 | else 31 | return false; 32 | } 33 | 34 | float Sharp_PM_2_5::GetConcentration() 35 | { 36 | return UD; 37 | } 38 | 39 | bool Sharp_PM_2_5::Check(u8 *Data,int Lenth,u8 CheckSum) 40 | { 41 | u8 temp =0; 42 | for(int i=0;i= 9) 24 | { 25 | com.GetBytes(temp, 9); 26 | CheckSum = sum((char*)temp, 9); 27 | if((temp[0] == 0xFF) && (temp[1] == 0xFF) && (CheckSum == temp[8])) 28 | { 29 | tempResult = (temp[4] * 256 + temp[5]); 30 | if(tempResult != 0){ 31 | mValue = (temp[4] * 256 + temp[5]); 32 | if(temp[6] != 0x00) 33 | mValue = mValue / (temp[6] * 10.0); 34 | mValue = mValue * temp[7]; 35 | } 36 | } 37 | } 38 | } 39 | 40 | float TVOC::GetValue(void) 41 | { 42 | return mValue; 43 | } 44 | -------------------------------------------------------------------------------- /libraries/OffChip/TVOC/TVOC.h: -------------------------------------------------------------------------------- 1 | #ifndef _TVOC_H_ 2 | #define _TVOC_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "FIFOBuffer.h" 6 | #include "USART.h" 7 | 8 | #define DHT12_ADDRESS 0xB8 9 | 10 | class TVOC{ 11 | 12 | private: 13 | USART &com; 14 | float mValue; 15 | public: 16 | TVOC(USART &uart); 17 | void Update(void); 18 | float GetValue(void); 19 | char sum(char *data, u8 num); 20 | }; 21 | 22 | #endif -------------------------------------------------------------------------------- /libraries/OffChip/Ultrasonic/Ultrasonic.h: -------------------------------------------------------------------------------- 1 | /* 2 | ********************************************************************************************************* 3 | * 4 | * Ultrasonic CALSS HEADER FILE 5 | * 6 | * Filename : Ultrasonic.h 7 | * Version : V1.1 8 | * Test module : HC-SR04 9 | * Programmer(s) : Jason Xie 10 | * 11 | ********************************************************************************************************* 12 | */ 13 | 14 | #ifndef _ULTRASONIC_H 15 | #define _ULTRASONIC_H 16 | 17 | #include "stm32f10x.h" 18 | 19 | #define MAX_SONAR_INTERVAL 0.25 //max interval time since last detection, unit: second 20 | #define MIN_SONAR_INTERVAL 0.02 //mix interval time since last detection, unit: second 21 | 22 | class Ultrasonic 23 | { 24 | protected: 25 | GPIO_TypeDef *mTrigPort; //GPIO Port of Trig pin 26 | GPIO_TypeDef *mEchoPort; //GPIO Port of Echo pin 27 | u16 mTrigPin; //GPIO pin for trig 28 | u16 mEchoPin; //GPIO pin for echo 29 | double mTrigTime; //trig time 30 | double mRiseTime; //rising edge time 31 | double mFallTime; //falling edge time 32 | float mMaxRange; //max detection range (cm) 33 | bool mIsReady; 34 | public: 35 | Ultrasonic(GPIO_TypeDef *trigPort, u8 trigPin, GPIO_TypeDef *echoPort, u8 echoPin, float maxRange=200,u8 itGroup=3,u8 prePriority=7,u8 subPriority=1); 36 | void IRQ(); //Interrupt Response Function 37 | u8 Update(float &dis); //Start a ultrasonic detection 38 | }; 39 | 40 | #endif 41 | -------------------------------------------------------------------------------- /libraries/OffChip/W25QXX/W25QXX.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/W25QXX/W25QXX.h -------------------------------------------------------------------------------- /libraries/OffChip/ZPH01/Senser.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef __SENSER_H 3 | #define __SENSER_H 4 | 5 | class Senser{ 6 | public: 7 | Senser(){}; 8 | virtual bool Updata()=0; 9 | // virtual unsigned short int GetU16Data()=0; 10 | virtual float GetFloatData()=0; 11 | virtual unsigned char Data_Hight_8() =0; 12 | virtual unsigned char Data_Low_8() =0; 13 | }; 14 | 15 | #endif 16 | -------------------------------------------------------------------------------- /libraries/OffChip/ZPH01/ZPH01.cpp: -------------------------------------------------------------------------------- 1 | #include "ZPH01.h" 2 | 3 | ZPH01::ZPH01(USART &usart):mUsart(usart) 4 | { 5 | 6 | } 7 | 8 | ZPH01::~ZPH01() 9 | { 10 | } 11 | 12 | 13 | bool ZPH01::Updata() 14 | { 15 | int num=mUsart.ReceiveBufferSize(); 16 | if(num%9!=0 || num>=90 ||num<9) 17 | { 18 | mUsart.ClearReceiveBuffer(); 19 | return false; 20 | } 21 | else 22 | { 23 | for(int i=0;i 17 | #include "USART.h" 18 | #include "Senser.h" 19 | 20 | class ZPH01:Senser 21 | { 22 | private: 23 | 24 | USART& mUsart; 25 | 26 | unsigned char mData[9]; //一帧数据大小 27 | 28 | float Concentration;//保存浓度值 29 | 30 | unsigned char FucCheckSum(unsigned char *i,unsigned char ln);//校验 31 | public: 32 | 33 | ZPH01(USART &usart); 34 | 35 | ~ZPH01(); 36 | 37 | u8 data_h;//保存浓度半分比的整数部分 38 | u8 data_l;//保存小数部分 39 | 40 | virtual bool Updata(); //更新 41 | virtual float GetFloatData(); //返回浓度值 单位ug/m3 42 | virtual unsigned char Data_Hight_8(); 43 | virtual unsigned char Data_Low_8(); 44 | 45 | }; 46 | 47 | 48 | #endif 49 | 50 | 51 | -------------------------------------------------------------------------------- /libraries/OffChip/esp8266/README.md: -------------------------------------------------------------------------------- 1 | esp8266 stm32 驱动封装 2 | ==== 3 | 4 | # 简介 5 | 使用stm32驱动使用AT指令驱动的esp8266模块 6 | 并封装了socket类,让使用更加简单 7 | 8 | # 环境 9 | C、C++、基于[stm32外设库](https://github.com/Neutree/STM32f103DriverLib) 10 | 11 | # 使用 12 | * 将文件夹内的5个文件复制并引入工程 13 | * 引入头文件、定义变量、资源装配、wifi初始化设置、wifi使用(socket接口(socket.h中)) 14 | * 代码 [(例程)](../../../example/offchip/esp8266/stm32f103c8t6) 15 | ```cpp 16 | #include "USART.h" 17 | #include "TaskManager.h" 18 | #include "Socket_esp8266.h" 19 | 20 | USART com(1,115200,false); 21 | Socket_esp8266 wifi(com); 22 | 23 | /*******************configuration****************/ 24 | char* mApJoinName ="lalala"; 25 | char* mApJoinPasswd="dd199511"; 26 | char* mServerIP = "192.168.1.104"; 27 | uint16_t mServerPort = 8989; 28 | /***********************************************/ 29 | 30 | char dataToSend[10]={1,2,3,4,5,6,7,8,9,10}; 31 | 32 | bool WiFiInit(void); 33 | 34 | int main() 35 | { 36 | TaskManager::DelayS(3); 37 | if(!WiFiInit()) 38 | { 39 | while(1); 40 | } 41 | wifi.Write(dataToSend,10); 42 | while(1); 43 | } 44 | 45 | bool WiFiInit() 46 | { 47 | wifi.Init();//初始化时一定要清除串口缓冲区,因为WiFi上电后回显很多调试信息,可能会造成串口缓冲区溢出,上电大于2秒后调用 48 | if(!wifi.Kick()) 49 | return false; 50 | wifi.SetEcho(false);//关闭回响 51 | wifi.SetMode(esp8266::esp8266_MODE_STATION,esp8266::esp8266_PATTERN_DEF);//设置为station模式 52 | wifi.SetMUX(false);//单连接模式 53 | wifi.JoinAP(mApJoinName,mApJoinPasswd,esp8266::esp8266_PATTERN_DEF);//加入AP 54 | TaskManager::DelayS(2); 55 | //连接服务器 56 | if(!wifi.Connect(mServerIP,mServerPort,Socket_Type_Stream,Socket_Protocol_IPV4)) 57 | return false; 58 | return true; 59 | } 60 | 61 | ``` -------------------------------------------------------------------------------- /libraries/OffChip/esp8266/Socket_esp8266.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OffChip/esp8266/Socket_esp8266.h -------------------------------------------------------------------------------- /libraries/OffChip/esp8266/esp8266.h: -------------------------------------------------------------------------------- 1 | #ifndef __ESP8266_H 2 | #define __ESP8266_H 3 | 4 | 5 | /** 6 | *@file esp8266.h 7 | *@brief The definition of class esp8266 and related operation of esp8266 module 8 | *@author neucrack(neucrack.com) CQUT IOT lib 9 | *@date 2015-11 10 | *@copyright CQUT IOT lib all right reserved 11 | */ 12 | 13 | 14 | 15 | #include "USART.h" 16 | #include "string.h" 17 | #include "TaskManager.h" 18 | #include "socket.h" 19 | #include "string.h" 20 | #include "stdlib.h" 21 | /*********************configuration****************************/ 22 | #define ESP8266_RECEIVE_BUFFER_SIZE 50 23 | #define ESP8266_DEFAULT_PATTERN esp8266_PATTERN_DEF 24 | #define ESP8266_DEFAULT_TIMEOUT 1 //单位:s 25 | 26 | /**************************************************************/ 27 | 28 | class esp8266 29 | { 30 | public: 31 | enum esp8266_pattern{ esp8266_PATTERN_NULL = 0, esp8266_PATTERN_CUR = 1, esp8266_PATTERN_DEF = 2 }; 32 | enum esp8266_MODE{ esp8266_MODE_STATION = 1, esp8266_MODE_AP = 2, esp8266_MODE_STATION_AP = 3 }; 33 | enum esp8266_ENCRYPTION{ 34 | esp8266_ENCRYPTION_OPEN = 0, esp8266_ENCRYPTION_WEP = 1, 35 | esp8266_ENCRYPTION_WPA_PSK = 2, esp8266_ENCRYPTION_WPA2_PSK = 3, esp8266_ENCRYPTION_WPA_WPA2_PSK = 4 36 | }; 37 | enum esp8266_ROLE{ esp8266_ROLE_SERVER = 1, esp8266_ROLE_CLIENT = 2 }; 38 | /** 39 | * Constuctor. 40 | * 41 | * @param uart - an reference of HardwareSerial object. 42 | * @param baudRate - the baud rate to communicate with ESP8266 when first power on (default:the same as usart's baud rate). 43 | * if the value is not the same as usart's baud rate, it will change usart's baud rate to the same as thid parameter's value 44 | * @warning parameter baud depends on the AT firmware. 9600 is an common value. 45 | */ 46 | esp8266(USART &usart, uint32_t baudRate = 0); 47 | 48 | void ClearBuffer(); 49 | 50 | bool Kick(void); 51 | bool Restart(void); 52 | bool GetVersion(char*); 53 | bool SetEcho(bool echo); 54 | bool Restore(void); 55 | bool SetUart(uint32_t baudrate, esp8266_pattern pattern); 56 | u8 GetCCSQ(char* WiFiSSID); //获取wifi信号 57 | 58 | bool SetMode(esp8266_MODE, esp8266_pattern = esp8266_PATTERN_DEF);//设置为station+ap模式 59 | bool SetMUX(bool isEnableMUX); 60 | bool SetApParam(char* apSetSsid, char* apSetPasswd, unsigned char channel = 1, esp8266_ENCRYPTION encryption = esp8266_ENCRYPTION_WPA2_PSK, esp8266_pattern = esp8266_PATTERN_DEF); 61 | bool JoinAP(char* apJoinSsid, char* apJoinPasswd, esp8266_pattern = esp8266_PATTERN_DEF);//加入AP 62 | bool QuitAP(void); 63 | 64 | bool CreateConnectMutipleMode(char* ipAddr, short port, Socket_Type socketType, signed char muxID = -1); 65 | bool SendMultipleMode(char* data, unsigned int num, signed char muxID = -1); 66 | bool Close(signed char muxID = -1); 67 | char GetStatus(char* muxID = 0, char* type = 0, char* ipAddr = 0, short remotePort = 0, short localPort = 0, esp8266_ROLE role = esp8266_ROLE_CLIENT); 68 | 69 | private: 70 | 71 | USART &mUsart; 72 | 73 | bool ReceiveAndWait(char const* targetString, unsigned char timeOut = ESP8266_DEFAULT_TIMEOUT); 74 | bool ReceiveAndWait(char const* targetString, char const* targetString2, unsigned char timeOut = ESP8266_DEFAULT_TIMEOUT); 75 | bool ReceiveAndWait(char const* targetString, char const* targetString2, char const* targetString3, unsigned char timeOut = ESP8266_DEFAULT_TIMEOUT); 76 | 77 | protected: 78 | char mReceiveBuffer[ESP8266_RECEIVE_BUFFER_SIZE]; 79 | unsigned int mReceiveBufferIndex; 80 | public: 81 | bool RecvFind(char const *target, unsigned char timeout = ESP8266_DEFAULT_TIMEOUT); 82 | bool RecvFind(char const *target, char const *target2, unsigned char timeout = ESP8266_DEFAULT_TIMEOUT); 83 | bool RecvFind(char const *target, char const *target2, char const *target3, unsigned char timeout = ESP8266_DEFAULT_TIMEOUT); 84 | bool RecvFindAndFilter(char const *target, char const * begin, char const * end, char* Data, float timeout = ESP8266_DEFAULT_TIMEOUT); 85 | 86 | 87 | }; 88 | #endif 89 | 90 | -------------------------------------------------------------------------------- /libraries/OffChip/esp8266/socket.h: -------------------------------------------------------------------------------- 1 | #ifndef __SOCKET_H 2 | #define __SOCKET_H 3 | #include "stdbool.h" 4 | 5 | enum Socket_Type{ Socket_Type_Stream, Socket_Type_Dgram };//TCP & UDP 6 | enum Socket_Protocol{ Socket_Protocol_IPV4, Socket_Protocol_IPV6 }; 7 | 8 | class Socket 9 | { 10 | public: 11 | Socket(){} 12 | virtual bool Init() = 0; 13 | virtual bool Connect(char* ipAddr, short int port, Socket_Type socketType, Socket_Protocol socketProtocol = Socket_Protocol_IPV4) = 0; 14 | virtual bool Write(char* data, unsigned int num) = 0; 15 | virtual unsigned int Read(char* data) = 0; 16 | virtual unsigned int Read(char* data, unsigned int num) = 0; 17 | virtual bool IsAlive() = 0; 18 | virtual bool Close() = 0; 19 | virtual void SetTimeOut(float timetOut) = 0; 20 | private: 21 | long int mIPAddr; 22 | short int mPort; 23 | 24 | }; 25 | 26 | #endif 27 | 28 | 29 | -------------------------------------------------------------------------------- /libraries/OffChip/yishan_PM2_5/yishan_PM2_5.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "yishan_PM2_5.h" 3 | 4 | yishan_PM_2_5::yishan_PM_2_5(USART &com):mCom(com) 5 | { 6 | PM1_0_UD=0; 7 | PM2_5_UD = 0; 8 | PM10_UD = 0; 9 | } 10 | 11 | bool yishan_PM_2_5::Check(u8 *Data,int Lenth,int CheckSum) 12 | { 13 | int temp=0; 14 | for(int i=0;i 31) 46 | { 47 | mCom.GetReceivedData(ch,2); 48 | if(ch[0] != 0x32 || ch[1] != 0x3d) 49 | { 50 | mCom.ClearReceiveBuffer(); 51 | return false; 52 | } 53 | // if(ch!=0x32) 54 | // return false; 55 | // else 56 | // { 57 | // mCom.GetReceivedData(&ch,1); 58 | // if(ch!=0x3D) 59 | // return false; 60 | // } 61 | mCom.GetReceivedData(data+2,30); 62 | data[0] = 0x32; 63 | data[1]= 0x3d; 64 | 65 | if(Check(data,30,(int)data[30]*256+data[31]))//校验 66 | { 67 | //数据处理 68 | PM1_0_UD = (int)data[4]*256 + data[5]; 69 | PM2_5_UD = (int)data[6]*256 + data[7]; 70 | PM10_UD = (int)data[8]*256 + data[9]; 71 | mCom.ClearReceiveBuffer(); 72 | return true; 73 | } 74 | else 75 | return false; 76 | } 77 | else 78 | return false; 79 | 80 | } 81 | -------------------------------------------------------------------------------- /libraries/OffChip/yishan_PM2_5/yishan_PM2_5.h: -------------------------------------------------------------------------------- 1 | /* 2 | 每秒发送一次,波特率9600 一个包长度为32个字节 3 | */ 4 | 5 | #ifndef __YISHAN_PM2_5_H__ 6 | #define __YISHAN_PM2_5_H__ 7 | 8 | #include "stm32f10x.h" 9 | #include "USART.h" 10 | 11 | class yishan_PM_2_5{ 12 | 13 | private: 14 | USART &mCom; 15 | int PM1_0_UD; 16 | int PM2_5_UD;//PM2.5浓度 单位 ug/m^3 17 | int PM10_UD; 18 | 19 | bool Check(u8 *Data,int Lenth,int CheckSum); 20 | 21 | public: 22 | yishan_PM_2_5(USART &com); 23 | 24 | bool Update(); 25 | int GetConcentration_2_5(); 26 | int GetConcentration_1_0(); 27 | int GetConcentration_10(); 28 | 29 | }; 30 | 31 | #endif 32 | 33 | -------------------------------------------------------------------------------- /libraries/OnChip/ADC/ADC.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OnChip/ADC/ADC.cpp -------------------------------------------------------------------------------- /libraries/OnChip/ADC/ADC.h: -------------------------------------------------------------------------------- 1 | #ifndef _ADC_H_ 2 | #define _ADC_H_ 3 | 4 | #include "stm32f10x.h" 5 | 6 | #define MAX_ADC_CHANNEL 10 7 | 8 | class ADC 9 | { 10 | private: 11 | static u16 _pin[MAX_ADC_CHANNEL]; //gpio pin for adc channel 12 | static bool _enCh[MAX_ADC_CHANNEL]; //enable flag for adc channel 13 | static u8 _chMap[MAX_ADC_CHANNEL]; //map channel number to the index of _adcValue 14 | static u16 _adcValue[MAX_ADC_CHANNEL]; //adc value for each channel 15 | public: 16 | ADC(u8 ch0Num, u8 ch1Num=0xFF, u8 ch2Num=0xFF, u8 ch3Num=0xFF, u8 ch4Num=0xFF, u8 ch5Num=0xFF, u8 ch6Num=0xFF, u8 ch7Num=0xFF, u8 ch8Num=0xFF, u8 ch9Num=0xFF); 17 | double operator[](u8 chNum); 18 | }; 19 | 20 | #endif 21 | 22 | -------------------------------------------------------------------------------- /libraries/OnChip/GPIO/GPIO.cpp: -------------------------------------------------------------------------------- 1 | 2 | //include the header file containing the class declaration. 3 | #include "GPIO.h" 4 | 5 | 6 | //Initialize the static member constants 7 | const uint16_t GPIO::mPin[16] = { GPIO_Pin_0, GPIO_Pin_1, GPIO_Pin_2, GPIO_Pin_3, GPIO_Pin_4, GPIO_Pin_5, GPIO_Pin_6, GPIO_Pin_7, 8 | GPIO_Pin_8, GPIO_Pin_9, GPIO_Pin_10, GPIO_Pin_11, GPIO_Pin_12, GPIO_Pin_13, GPIO_Pin_14, GPIO_Pin_15 }; 9 | 10 | 11 | //The Constructor of the Class 12 | GPIO::GPIO(GPIO_TypeDef *port, uint16_t pin, GPIOMode_TypeDef mode, GPIOSpeed_TypeDef speed) :mMode(mode), mSpeed(speed), mPort(port), mSelectPin(pin) 13 | { 14 | GPIO_InitTypeDef GPIO_InitStructure; 15 | RCC_Configuration(); 16 | GPIO_InitStructure.GPIO_Pin = mPin[pin]; 17 | GPIO_InitStructure.GPIO_Speed = speed; 18 | GPIO_InitStructure.GPIO_Mode = mode; 19 | GPIO_Init(mPort, &GPIO_InitStructure); 20 | } 21 | 22 | //The function to configure the RCC of GPIO 23 | void GPIO::RCC_Configuration() 24 | { 25 | // SystemInit(); //系统设置初始化 26 | if (mPort == GPIOA) 27 | { 28 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); 29 | } 30 | else if (mPort == GPIOB) 31 | { 32 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); 33 | } 34 | else if (mPort == GPIOC) 35 | { 36 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE); 37 | } 38 | else if (mPort == GPIOD) 39 | { 40 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD, ENABLE); 41 | } 42 | else if (mPort == GPIOE) 43 | { 44 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOE, ENABLE); 45 | } 46 | else if (mPort == GPIOF) 47 | { 48 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF, ENABLE); 49 | } 50 | else if (mPort == GPIOG) 51 | { 52 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOG, ENABLE); 53 | } 54 | } 55 | 56 | /** 57 | * @brief Set the level of the pin 58 | * @param level:The level you wan to set,value:0 or 1 59 | */ 60 | void GPIO::SetLevel(u8 level) 61 | { 62 | if (level > 0) 63 | GPIO_SetBits(mPort, mPin[mSelectPin]); 64 | else 65 | GPIO_ResetBits(mPort, mPin[mSelectPin]); 66 | } 67 | 68 | /** 69 | * @brief Get the level of the pin 70 | * @retval level:Return the pin's level,value:true(1),false(0) 71 | */ 72 | bool GPIO::GetLevel() 73 | { 74 | if (!GPIO_ReadInputDataBit(mPort, mPin[mSelectPin])) 75 | return false; 76 | else 77 | return true; 78 | } 79 | 80 | /*** Invert the level of the pin ***/ 81 | void GPIO::Toggle() 82 | { 83 | if (GPIO_ReadInputDataBit(mPort, mPin[mSelectPin])) 84 | GPIO_ResetBits(mPort, mPin[mSelectPin]); 85 | else 86 | GPIO_SetBits(mPort, mPin[mSelectPin]); 87 | } 88 | 89 | void GPIO::ChangeMode(GPIOMode_TypeDef mode) 90 | { 91 | GPIO_InitTypeDef GPIO_InitStructure; 92 | 93 | GPIO_InitStructure.GPIO_Pin = mPin[mSelectPin]; 94 | GPIO_InitStructure.GPIO_Speed = mSpeed; 95 | GPIO_InitStructure.GPIO_Mode = mode; 96 | GPIO_Init(mPort, &GPIO_InitStructure); 97 | } 98 | 99 | -------------------------------------------------------------------------------- /libraries/OnChip/GPIO/GPIO.h: -------------------------------------------------------------------------------- 1 | /* 2 | ********************************************************************************************************* 3 | * 4 | * GPIO CALSS HEADER FILE 5 | * 6 | * Filename : GPIO.h 7 | * Version : V1.0 8 | * Programmer(s) : Jason Xie 9 | * 10 | ********************************************************************************************************* 11 | */ 12 | #ifndef _GPIO_H 13 | #define _GPIO_H 14 | 15 | /** include header files **/ 16 | 17 | #include 18 | #include "stm32f10x_gpio.h" 19 | #include "stm32f10x_rcc.h" 20 | #include 21 | #include 22 | 23 | 24 | /** 25 | * @brief The class of GPIO. 26 | * @param mPin[16]: The array of GPIO_Pin_x. 27 | * @param mPort:The port of GPIO,such as GPIOA,etc. 28 | * @param mSelectPin:The pin you want to use. 29 | * @param mMode:The GPIO's mode,such as "GPIO_Mode_Out_PP",etc 30 | * @param mSpeed:The output's speed of GPIO,such as "GPIO_Speed_10MHz",etc 31 | */ 32 | class GPIO 33 | { 34 | private: 35 | static const uint16_t mPin[16]; 36 | 37 | GPIOMode_TypeDef mMode; 38 | GPIOSpeed_TypeDef mSpeed; 39 | 40 | /* The function to configure the RCC of GPIO */ 41 | void RCC_Configuration(); 42 | public: 43 | GPIO_TypeDef *mPort; 44 | uint16_t mSelectPin; 45 | 46 | /* The Constructor of the Class */ 47 | GPIO(GPIO_TypeDef *port = GPIOA, uint16_t pin = 1, GPIOMode_TypeDef mode = GPIO_Mode_Out_PP, GPIOSpeed_TypeDef speed = GPIO_Speed_50MHz); 48 | 49 | /** 50 | * @brief Set the pin as high level or low level. 51 | * @param level: The level you wan to set,type:unsigned char ,value:0 or 1 52 | */ 53 | void SetLevel(u8 level); 54 | 55 | /** 56 | * @brief Get the level of the pin. 57 | * @retval level:Return the pin's level,value:true(1),false(0) 58 | */ 59 | bool GetLevel(); 60 | 61 | /** 62 | * @brief Invert the level of the pin. 63 | */ 64 | void Toggle(); 65 | 66 | /** 67 | * @brief Change the GPIO's mode. 68 | * @param the GPIO's mode 69 | */ 70 | void ChangeMode(GPIOMode_TypeDef mode); 71 | }; 72 | 73 | 74 | #endif 75 | 76 | -------------------------------------------------------------------------------- /libraries/OnChip/IIC/I2C.h: -------------------------------------------------------------------------------- 1 | #ifndef _I2C_H_ 2 | #define _I2C_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "stm32f10x_gpio.h" 6 | #include "stm32f10x_rcc.h" 7 | #include "FIFOBuffer.h" 8 | #include "Sensor.h" 9 | 10 | #define I2C_QUEUE_SIZE 50 11 | 12 | 13 | struct I2C_Command 14 | { 15 | u8 slaveAddr; //slave address 16 | u8 dataOut[5]; //data send to slave 17 | u8 outDataLen; //number of bytes send to slave 18 | u8* pDataIn; //ponter to receive data from slave 19 | u8 inDataLen; //number of bytes to recieve from slave 20 | u8 isTaskTail; // 21 | Sensor *pDevice; // 22 | }; 23 | 24 | 25 | class I2C 26 | { 27 | private: 28 | I2C_TypeDef* mI2C; //i2c device name 29 | u32 mSpeed; //i2c bus speed 30 | bool mRemap; //whether gpio pin remap 31 | u16 mSDAPin; //gpio pin of sda 32 | u16 mSCLPin; //gpio pin of scl 33 | u32 mI2CRcc; //i2c clock 34 | u32 mPriGroup; //Priority Group 35 | u8 mEvtIRQ; //i2c event irqn 36 | u8 mErrIRQ; //i2c error irqn 37 | u8 mEvtPre; //event preemption priority 38 | u8 mEvtSub; //event sub priority 39 | u8 mErrPre; //error preemption priority 40 | u8 mErrSub; //error sub priority 41 | u8 mState; //i2c bus state flag 42 | FIFOBuffer mCmdBank; 43 | 44 | u8 mDataIdx; //index of Tx / Rx data 45 | u8 mI2CDirection; //I2C Direction (Tx / Rx) 46 | I2C_Command mCurCmd; //Current I2C Command 47 | int mErrorCnt; //I2C Bus error counter 48 | private: 49 | bool Reset(); 50 | void InitGPIO(GPIOMode_TypeDef gpioMode); 51 | void InitI2C(); 52 | void InitNVIC(); 53 | bool StartNextCmd(); 54 | public: 55 | I2C(I2C_TypeDef* i2c, u32 speed=400000,u8 remap=0,u8 priGroup=3,u8 preEvt=0,u8 subEvt=0,u8 preErr=0,u8 subErr=0); 56 | bool Initialize(); 57 | bool AddCommand(u8 slaveAddr,u8 txData[], u8 txNum, u8 rxData[], u8 rxNum, Sensor *pDevice, bool isTaskTail); 58 | bool Start(); 59 | bool IsHealthy(); 60 | bool IsFree(); 61 | bool WaitFree(u16 ms=2); 62 | void EventIRQ(); 63 | void ErrorIRQ(); 64 | int I2CErrors() { return mErrorCnt; } 65 | }; 66 | 67 | #define I2C_STATE_NULL 0x00 68 | #define I2C_STATE_START 0x01 69 | #define I2C_STATE_ADDR 0x02 70 | #define I2C_STATE_TXMOD 0x03 71 | #define I2C_STATE_RXMOD 0x04 72 | #define I2C_STATE_TX 0x05 73 | #define I2C_STATE_RX 0x06 74 | #define I2C_STATE_STOP 0x07 75 | #define I2C_STATE_FREE 0x08 76 | #define I2C_STATE_ERROR 0x09 77 | 78 | #endif 79 | 80 | 81 | -------------------------------------------------------------------------------- /libraries/OnChip/IIC/I2CDevice.h: -------------------------------------------------------------------------------- 1 | #ifndef _SENSOR_H_ 2 | #define _SENSOR_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "TaskManager.h" 6 | 7 | class Sensor 8 | { 9 | protected: 10 | bool mHealthy; 11 | bool mIsUpdated; //I2C task complete falg 12 | double mUpdatedTime; //I2C task completed time (second) 13 | double mInterval; //time interval since last update (second) 14 | public: 15 | Sensor() 16 | { 17 | mHealthy = false; 18 | mIsUpdated = true; 19 | mUpdatedTime = 0; 20 | mInterval = 0; 21 | } 22 | void Updated() 23 | { 24 | static double curTime; 25 | mIsUpdated = true; 26 | curTime= tskmgr.Time(); 27 | mInterval = curTime - mUpdatedTime; 28 | mUpdatedTime = curTime; 29 | } 30 | float Interval() { return mInterval; } //return interval between two update 31 | bool IsHealthy() { return mHealthy; } //return healthy state of device 32 | }; 33 | 34 | 35 | #endif 36 | 37 | 38 | 39 | 40 | 41 | 42 | -------------------------------------------------------------------------------- /libraries/OnChip/IIC/IIC.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OnChip/IIC/IIC.cpp -------------------------------------------------------------------------------- /libraries/OnChip/IIC/IIC.h: -------------------------------------------------------------------------------- 1 | #ifndef _IIC_H_ 2 | #define _IIC_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "stm32f10x_i2c.h" 6 | #include "FIFOBuffer.h" 7 | 8 | //i2c command type 9 | enum IIC_CMD_Type 10 | { 11 | OUT2IN = 0x01, //read one byte from given register of slave 12 | IN2OUT = 0x02, //read multi bytes from continue registers of slave 13 | }; 14 | 15 | //data structure of one i2c command 16 | struct IIC_Command 17 | { 18 | IIC_CMD_Type cmdType; //type of i2c commmand 19 | u8 slaveAddr; //slave address 20 | u8 DataOut[5]; //data send to slave 21 | u8 outDataLen; //number of bytes send to slave 22 | u8* pDataIn; //ponter to receive data from slave 23 | u8 inDataLen; //number of bytes to recieve from slave 24 | }; 25 | 26 | //class type for IIC bus 27 | class IIC 28 | { 29 | private: 30 | I2C_TypeDef* _i2c; //the device pointer of i2c 31 | u32 _i2c_speed; //speed of i2c bus 32 | u16 _scl_pin; //gpio pin of scl 33 | u16 _sda_pin; //gpio pin of sda 34 | u32 _i2c_rcc; //rcc of gpio for i2c pin 35 | u8 _gpio_remap; //flag of gpio pin remap 36 | bool _healthy; //healthy of i2c (master or slave) 37 | u32 _evt_irq_cnt; //i2c event interrupt counter in one i2c command, if larger than a given number, reset i2c 38 | //interrupt setting 39 | u8 _evt_irqn; //i2c event IRQn 40 | u8 _err_irqn; //i2c error IRQn 41 | u8 _evt_subprio; //i2c event interrupt sub priority 42 | u8 _evt_preprio; //i2c event interrupt preemption priority 43 | u8 _err_subprio; //i2c error interrupt sub priority 44 | u8 _err_preprio; //i2c error interrupt preemption priority 45 | 46 | //i2c command related varible 47 | FIFOBuffer _i2c_cmd_queue; //i2c command queue 48 | IIC_Command _current_cmd; //current i2c command 49 | u8 _i2c_direction; //current i2c direction (send or receive) 50 | u8 _i2c_tx_cnt; //i2c transmit bytes counter within one i2c command 51 | u8 _i2c_rx_cnt; //i2c receive bytes counter within one i2c command 52 | 53 | private: 54 | void InitGPIO(void); //initialize gpio of i2c 55 | void SetDefaultGPIO(void);//set gpio as default io 56 | void Check_Busy_Fix(void); //check the BUSY bit of i2c device, and fix it if BUSY=1 57 | public: 58 | ///constructor, for i2c initialize 59 | ///@param i2c: i2c select 60 | ///@param speed: speed of i2c bus 61 | ///@param remap: gpio remap flag 62 | IIC(I2C_TypeDef* i2c = I2C1, u32 speed = 400000, u8 remap = 0); //construct function 63 | void Initialize(void); //initilize i2c device 64 | bool StartNextCommand(void); //transfer command from iic_cmd_queue to iic_cmd_current 65 | void Reset(void); //reset i2c bus 66 | bool AddCommand(u8 slaveAddr, IIC_CMD_Type cmdType, u8 *pTxData, u8 txNum, u8 *pRxData, u8 rxNum);//add command to i2c command queue 67 | void ClearCommand(); //clear all i2c command in queue 68 | void EventIRQ(void); //i2c event interrupt handler 69 | void ErrorIRQ(void); //i2c error interrupt handler 70 | bool IsWorkingAndFree(); 71 | }; 72 | 73 | 74 | #endif 75 | 76 | -------------------------------------------------------------------------------- /libraries/OnChip/InputCapture/InputCapture_EXIT.h: -------------------------------------------------------------------------------- 1 | #ifndef _INPUT_CAPTURE_EXIT_H_ 2 | #define _INPUT_CAPTURE_EXIT_H_ 3 | 4 | #include "stm32f10x.h" 5 | 6 | class InputCapture_EXIT 7 | { 8 | protected: 9 | GPIO_TypeDef *mExitPort; //GPIO Port of exit pin 10 | u16 mExitPin; //GPIO pin for exit 11 | double mRiseTime; //rising edge time 12 | double mFallTime; //falling edge time 13 | double mInterval; //time between rising edge and falling edge 14 | public: 15 | InputCapture_EXIT(GPIO_TypeDef *exitPort, u8 exitPin, u8 itGroup=3,u8 prePriority=5,u8 subPriority=0); 16 | void IRQ(); 17 | double Value(); 18 | }; 19 | 20 | 21 | 22 | 23 | 24 | #endif 25 | -------------------------------------------------------------------------------- /libraries/OnChip/InputCapture/InputCapture_TIM.h: -------------------------------------------------------------------------------- 1 | /******************************************************************************** 2 | * @file InputCapture.h 3 | * @author lissettecarlr(creat) 4 | * @version V1.0 5 | * @date 10/26/2015 6 | * @brief TIMx CH1 CH2 CH3 CH4 7 | * 1 PA8 PA9 PA10 PA11 8 | * 2 PA0 PA1 PA2 PA3 9 | * 3 PA6 PA7 PB0 PB1 10 | * 4 PB6 PB7 PB8 PB9 11 | * @attention USART1.Rx = TIM1.CH2, USART1.Tx = TIM1.CH3 12 | ****************************************************************************** 13 | */ 14 | 15 | #ifndef __INPUT_CAPTURE_H_ 16 | #define __INPUT_CAPTURE_H_ 17 | 18 | 19 | #include "stm32f10x.h" 20 | 21 | class InputCapture_TIM 22 | { 23 | private: 24 | TIM_TypeDef *_TIMx; //timer for capture function 25 | double _resolution; //the time for one tick of counter (ms/tick) 26 | u16 _ch1Cnt; //count of ticks for channel1 27 | u16 _ch2Cnt; //count of ticks for channel2 28 | u16 _ch3Cnt; //count of ticks for channel3 29 | u16 _ch4Cnt; //count of ticks for channel4 30 | 31 | u16 _ch1Pin; //gpio pin for channel1 32 | u16 _ch2Pin; //gpio pin for channel2 33 | u16 _ch3Pin; //gpio pin for channel3 34 | u16 _ch4Pin; //gpio pin for channel4 35 | bool _enCh1; //channel 1 enable flag 36 | bool _enCh2; //channel 2 enable flag 37 | bool _enCh3; //channel 3 enable flag 38 | bool _enCh4; //channel 4 enable flag 39 | 40 | GPIO_TypeDef *_port, *_port2; //gpio port 41 | u8 _IRQn; //IRQ channel 42 | u32 _timer_rcc; //clock of timer 43 | u32 _gpio_rcc; //clock of gpio 44 | u32 _prescaler; //prescaler of timer 45 | u32 _period; //period of timer 46 | public: 47 | InputCapture_TIM(TIM_TypeDef *TIMx, u16 minHz, bool enCh1=false, bool enCh2=false, bool enCh3=false, bool enCh4=false, u8 intGroup=2,u8 prePriority=2,u8 subPriority=2); 48 | void Start(); //start timer 49 | void Stop(); //stop timer 50 | void IRQ(); //interrupt response function 51 | double operator[](u8 chNum); //return capture channel value, ms 52 | }; 53 | 54 | 55 | #endif 56 | -------------------------------------------------------------------------------- /libraries/OnChip/PWM/PWM.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OnChip/PWM/PWM.cpp -------------------------------------------------------------------------------- /libraries/OnChip/PWM/PWM.h: -------------------------------------------------------------------------------- 1 | #ifndef _F103_PWM_H_ 2 | #define _F103_PWM_H_ 3 | 4 | #include "stm32f10x.h" 5 | 6 | class PWM 7 | { 8 | private: 9 | u32 _timx_rcc; //timer rcc 10 | u32 _gpio_rcc; //gpio rcc 11 | TIM_TypeDef *_timx; //timer 12 | GPIO_TypeDef *_port; //gpio 13 | u16 _pin1; //ch1 gpio pin 14 | u16 _pin2; //ch2 gpio pin 15 | u16 _pin3; //ch3 gpio pin 16 | u16 _pin4; //ch4 gpio pin 17 | bool _enCh1; //ch1 enable flag 18 | bool _enCh2; //ch2 enable flag 19 | bool _enCh3; //ch3 enable falg 20 | bool _enCh4; //ch4 enable falg 21 | u16 _frqence; //freqence 22 | u32 _period; //period 23 | u16 _prescaler; //prescaler 24 | public: 25 | PWM(TIM_TypeDef *timx,bool enCh1,bool enCh2,bool enCh3, bool enCh4, u16 frq); 26 | void Initialize(TIM_TypeDef *timx,bool enCh1,bool enCh2,bool enCh3, bool enCh4, u16 frq); 27 | void SetDuty(float ch1,float ch2, float ch3, float ch4=0); 28 | void SetDuty(u8 chNum,float ch2); 29 | }; 30 | 31 | 32 | 33 | #endif 34 | -------------------------------------------------------------------------------- /libraries/OnChip/SPI/SPI.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OnChip/SPI/SPI.cpp -------------------------------------------------------------------------------- /libraries/OnChip/SPI/SPI.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OnChip/SPI/SPI.h -------------------------------------------------------------------------------- /libraries/OnChip/SerialPort/USART.h: -------------------------------------------------------------------------------- 1 | 2 | /** 3 | *@file USART.h 4 | *@author 2015-20-28 Neutree 5 | *@version v1.1 6 | *@brief stm32f10x串口驱动文件,使用时引入 USART.h USART.cpp FIFOBuffer.h Interrupt.h Interrupt.cpp 五个文件, 7 | * 然后根据需要配置USART.h中开头的配置部分(缓冲区大小配置) 8 | * 中断均由Interrupt.cpp中管理,若需要自定义,请自行编辑中断函数 9 | * 然后定义对象初始化,既可以使用 10 | *@copyright CQUTIOTLIB all right reserved 11 | * 12 | */ 13 | #ifndef __USART_H 14 | #define __USART_H 15 | #include "stm32f10x.h" 16 | #include "FIFOBuffer.h" 17 | #include "Configuration.h" 18 | 19 | 20 | /** 21 | *@addtogroup USART_CONFIGURATION 22 | *@{ 23 | */ 24 | /******************************************************************************************************/ 25 | /****configuration,使用前请自行配置****/ 26 | #define USART_TX_BUFFER_SIZE 200 //USART BUFFER FIFO SIZE 27 | #define USART_RX_BUFFER_SIZE 200 //USART BUFFER FIFO SIZE 28 | #define USART_DMA_TX_BUFFER_SIZE 200 //USART DMA BUFFER SIZE 29 | 30 | /*******************************************************************************************************/ 31 | 32 | class USART 33 | { 34 | private: 35 | bool isBusySend; 36 | 37 | u32 mBaudrate; //baudrate of usart 38 | u16 mParity; //parity of usart 39 | u16 mWordLen; //world length of usart 40 | u16 mStopBits; //stop bits of usart 41 | u16 mTxPin; //Tx gpio pin 42 | u16 mRxPin; //Rx gpio pin 43 | u8 mIRQn; //USART IRQn 44 | GPIO_TypeDef* mPort; //GPIO port 45 | USART_TypeDef* mUSARTx; //USARTx 46 | u32 mGPIORcc; //GPIO Clock 47 | u32 mUSARTRcc; //USART Clock 48 | bool mRemap; //gpio remap flag 49 | u8 mPrePri; //preemption priority 50 | u8 mSubPri; //sub priority 51 | u8 mPriGroup; //priority group 52 | FIFOBuffer mTxBuf; //USART Tx Buffer 53 | FIFOBuffer mRxBuf; //USART Rx Buffer 54 | 55 | u8 mPrecision; //when show precision after dot "." when use "<<" to show float value 56 | 57 | u16 mTxOverflow; //Tx overflow byte count 58 | u16 mRxOverflow; //Rx overflow byte count 59 | 60 | private: 61 | void InitGPIO(); 62 | void InitUSART(); 63 | void InitNVIC(); 64 | public: 65 | USART(USART_TypeDef* USARTx,u32 baud,u8 priGroup=3,u8 prePri=7,u8 subPri=1,bool remap=false,u16 parity=USART_Parity_No,u16 wordLen=USART_WordLength_8b, u16 stopBits=USART_StopBits_1); 66 | void Initialize(); 67 | 68 | ////////////////////////// 69 | ///@bief 设置波特率 70 | ///@param baudRate 波特率大小 71 | ////////////////////////// 72 | void SetBaudRate(uint32_t baudRate); 73 | 74 | virtual bool SendBytes(u8 txData[], u16 size); 75 | virtual bool SendByte(u8 data); 76 | virtual bool GetBytes(u8 data[],u16 num); 77 | virtual bool GetByte(u8 &data); 78 | 79 | virtual u16 TxSize(); 80 | virtual u16 RxSize(); 81 | 82 | virtual u16 TxOverflowSize(); 83 | virtual u16 RxOverflowSize(); 84 | 85 | virtual void ClearRxBuf(); 86 | virtual void ClearTxBuf(); 87 | 88 | bool CheckFrame(DataFrame &df); 89 | 90 | void IRQ(); 91 | 92 | USART& operator<<(int val); 93 | USART& operator<<(double val); 94 | USART& operator<<(const char* pStr); 95 | 96 | #ifdef USE_USART_DMA 97 | private: 98 | u8 mDMAIRQn; 99 | DMA_Channel_TypeDef* mDMATxCh; 100 | u32 mDMATCFlag; 101 | u32 mDMAGLFlag; 102 | u8 mDMATxBuf[USART_DMA_TX_BUFFER_SIZE]; 103 | void InitDMA(); 104 | public: 105 | void DMAIRQ(); 106 | #endif 107 | }; 108 | 109 | /** 110 | =========================================================================== 111 | | remap value | 112 | usartName | 0x00 | 0x01 | 0x11 | 113 | usart1Tx | PA9 | PB6 | | 114 | usart1Rx | PA10 | PB7 | | 115 | usart2Tx | PA2 | PD5 | | 116 | usart2Rx | PA3 | PD6 | | 117 | usart3Tx | PB10 | PC10 | PD8 | 118 | usart3Rx | PB11 | PC11 | PD9 | 119 | =========================================================================== 120 | */ 121 | 122 | #endif 123 | -------------------------------------------------------------------------------- /libraries/OnChip/SoftwareI2C/SoftwareI2C.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OnChip/SoftwareI2C/SoftwareI2C.cpp -------------------------------------------------------------------------------- /libraries/OnChip/SoftwareI2C/SoftwareI2C.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OnChip/SoftwareI2C/SoftwareI2C.h -------------------------------------------------------------------------------- /libraries/OnChip/SoftwareI2C/sys/sys.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OnChip/SoftwareI2C/sys/sys.c -------------------------------------------------------------------------------- /libraries/OnChip/SoftwareI2C/sys/sys.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/OnChip/SoftwareI2C/sys/sys.h -------------------------------------------------------------------------------- /libraries/OnChip/Timer/Timer.cpp: -------------------------------------------------------------------------------- 1 | #include "Timer.h" 2 | 3 | Timer::Timer(TIM_TypeDef *timer,u16 second,u16 millisecond,u16 microsecond,u8 Prioritygroup,u8 preemprionPriority,u8 subPriority) 4 | { 5 | 6 | //通过计算的出了ARR PSC 7 | uint8_t timerIrqChannel; 8 | TIM_TimeBaseInitTypeDef TIM_BaseInitStructure; 9 | mTempTimer=timer; 10 | NVIC_InitTypeDef NVIC_InitStructure; 11 | Conversion(second,millisecond,microsecond); 12 | 13 | if(timer==TIM1) 14 | { 15 | RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); 16 | timerIrqChannel=TIM1_UP_IRQn; 17 | 18 | } 19 | else if(timer==TIM2) 20 | { 21 | RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); 22 | timerIrqChannel=TIM2_IRQn; 23 | } 24 | else if(timer==TIM3) 25 | { 26 | RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); 27 | timerIrqChannel=TIM3_IRQn; 28 | } 29 | else if(timer==TIM4) 30 | { 31 | RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); 32 | timerIrqChannel=TIM4_IRQn; 33 | } 34 | else 35 | { 36 | 37 | } 38 | //TIM_InternalClockConfig(timer); 39 | 40 | // TIM_DeInit(timer);//将寄存器重设为缺省值 41 | TIM_BaseInitStructure.TIM_Period = mArr-1; //设置初值 42 | TIM_BaseInitStructure.TIM_Prescaler =mPsc-1;//设置预分频 43 | TIM_BaseInitStructure.TIM_ClockDivision = 0;//设置时钟分割 44 | TIM_BaseInitStructure.TIM_RepetitionCounter=0; 45 | TIM_BaseInitStructure.TIM_CounterMode = TIM_CounterMode_Up;//设置计数方式 46 | TIM_TimeBaseInit(timer,&TIM_BaseInitStructure); 47 | TIM_ClearFlag(timer, TIM_FLAG_Update);//清空中断标识 写了就进不了中断了 48 | TIM_ITConfig(timer, TIM_IT_Update, ENABLE); //使能中断 49 | 50 | switch(Prioritygroup)//中断分组 51 | { 52 | case 0: 53 | NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0); 54 | break; 55 | case 1: 56 | NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1); 57 | break; 58 | case 2: 59 | NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2); 60 | break; 61 | default: 62 | NVIC_PriorityGroupConfig(NVIC_PriorityGroup_3); 63 | break; 64 | case 4: 65 | NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4); 66 | break; 67 | } 68 | NVIC_InitStructure.NVIC_IRQChannel =timerIrqChannel; 69 | NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = preemprionPriority; //先占优先 70 | NVIC_InitStructure.NVIC_IRQChannelSubPriority = subPriority; //从优先 71 | NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //IRQ通道被使能 72 | NVIC_Init(&NVIC_InitStructure); //初始化NVIC寄存器 73 | TIM_Cmd(mTempTimer, ENABLE);//开启定时器 74 | /**/ 75 | } 76 | 77 | void Timer::Start() 78 | { 79 | TIM_Cmd(mTempTimer, ENABLE);//开启定时器 80 | } 81 | 82 | void Timer::Stop() 83 | { 84 | TIM_Cmd(mTempTimer,DISABLE);//关闭定时器 85 | } 86 | 87 | 88 | 89 | /* 90 | 算法思路: 91 | COEFFICIENT表示1分屏时最大的时间 92 | 首先判断是否可以用一分频解决,如果不能,则计算出相近的预分频 93 | 然后判断是是否能用此预分频得到一个整数初值,如果不能则预分频加一在继续查找 94 | 如果始终未查找到能够整除的预分频和初值,则使用一开始的初始预分频,然后计算出 95 | 一个相近的初值来代替。 96 | */ 97 | void Timer::Conversion(u16 s,u16 ms,u16 us) //将时分秒转化为预分频和初值 98 | { 99 | u32 time; 100 | u16 tempPsc;//用于暂存计算值 101 | u32 tempArr=0xfffff; 102 | 103 | 104 | time=s*1000000+ms*1000+us; //计算总时间 单位us 105 | if(time0xffff ) && mPsc<=65535)//如果计算的初值是个整数,或者没有找到可以计算出整数的分频数 114 | { 115 | mPsc++; 116 | tempArr=(time*72)/mPsc; //计算出初值 117 | } 118 | 119 | if(mPsc>=65535) //如果找到能够整除的分频值,则选用精度最大的分频值 120 | { 121 | mPsc=tempPsc; 122 | tempArr=(time*72)/mPsc; //计算出初值 123 | } 124 | else 125 | mArr=tempArr; 126 | 127 | 128 | 129 | } 130 | 131 | void Timer::OnOrOffIrq(bool Switch) 132 | { 133 | if (Switch==true) 134 | mTempTimer->DIER|=1<<0; //使能更新中断 135 | else 136 | mTempTimer->DIER&=0<<0; //关闭更新中断 137 | } 138 | 139 | void Timer::ClearCNT(void) 140 | { 141 | mTempTimer->CNT &=0; 142 | } 143 | 144 | -------------------------------------------------------------------------------- /libraries/OnChip/Timer/Timer.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file Timer.h 4 | * @author lissettecarlr 5 | * @version V1.0 6 | V1.1 增加开关中断功能 7 | V1.2 增加清除CNT计数器的值的功能 8 | 9 | * @date 10/25/2015(create) 10 | 10/28/2015(Debug) 11 | 11/02/2015(add) 12 | * @brief 必须配套Interrupt文件使用,用户如需需要编写中断函数,直接编写 13 | TIMX CH1 CH2 CH3 CH4 14 | 1 PA8 PA9 PA10 PA11 15 | 2 PA0 PA1 PA2 PA3 16 | 3 PA6 PA7 PB0 PB1 17 | 4 PB6 PB7 PB8 PB9 18 | ****************************************************************************** 19 | */ 20 | 21 | #ifndef __TIMER_H 22 | #define __TIMER_H 23 | 24 | /* Includes ------------------------------------------------------------------*/ 25 | extern "C"{ 26 | #include "stm32f10x.h" 27 | } 28 | 29 | /* define -------------------------------------------------------------------*/ 30 | //#define COEFFICIENT 66446 31 | #define COEFFICIENT 911 32 | // 65535/72 33 | /* class----------------------------------------------------------------------*/ 34 | 35 | class Timer{ 36 | private: 37 | u16 mArr;//计数器初值 38 | u16 mPsc;//计数器预分频 39 | TIM_TypeDef *mTempTimer;//时钟选择 40 | void Conversion(u16 s,u16 ms,u16 us);//将时分秒转换为初值和预分频 41 | 42 | public: 43 | //////////////////////////////////////// 44 | ///定时器初始化,默认定时器1,定时1ms 45 | ///@param timer 选择使用的定时器 46 | ///@param Prioritygroup 中断分组 47 | ///@param preemprionPriority 抢占优先级 48 | ///@param subPriority 响应优先级 49 | ///@param second 秒 50 | ///@param millisecond 毫秒 51 | ///@param microsecond 微秒 52 | //////////////////////////////////////// 53 | Timer(TIM_TypeDef *timer=TIM1,u16 second=0,u16 millisecond=1,u16 microsecond=0,u8 Prioritygroup=2,u8 preemprionPriority=2,u8 subPriority=2); 54 | 55 | //////////////////// 56 | ///开启定时器 57 | /////////////////// 58 | void Start(); 59 | 60 | /////////////////// 61 | ///关闭定时器 62 | ////////////////// 63 | void Stop(); 64 | ///////////////////////////////////////// 65 | ///关闭定时器 66 | ///@param bool true 开启中断 false 关闭中断 67 | ////////////////////////////////////////// 68 | void OnOrOffIrq(bool Switch); 69 | 70 | /////////////////// 71 | ///清空计数器的值 72 | ////////////////// 73 | void ClearCNT(void); 74 | 75 | 76 | }; 77 | 78 | #endif 79 | -------------------------------------------------------------------------------- /libraries/System/TaskManager/TaskManager.cpp: -------------------------------------------------------------------------------- 1 | #include "TaskManager.h" 2 | 3 | #include "USART.h" 4 | extern USART com1; 5 | 6 | double TaskManager::_it_time = 0; 7 | u16 TaskManager::_lose_tick_cnt = 0; 8 | double TaskManager::_old_time = 0; 9 | 10 | //Constructor 11 | TaskManager::TaskManager() 12 | { 13 | 14 | SysTick->CTRL &= 0xFFFFFFF8; //Clock div 8 = 9M, disable INT, disable count 15 | SysTick->LOAD = 16200000; //1.8s 16 | SysTick->VAL = 0; 17 | SysTick->CTRL |= 0x00000003; //ENABLE count + INT 18 | for(volatile int i=0; i<1000;i++); 19 | } 20 | //get current time since power on 21 | double TaskManager::Time() 22 | { 23 | double curTime = _it_time + 1.8 - SysTick->VAL/9000000.0; //update current time 24 | 25 | double dt = curTime - _old_time; 26 | 27 | if(dt < -1) //not INT, VAL reload(-1.8s) 28 | { 29 | curTime += 1.8; 30 | } 31 | else if(dt>1.79) 32 | { 33 | curTime -= 1.8; 34 | } 35 | _old_time = curTime; //update old time 36 | return curTime; 37 | } 38 | 39 | void TaskManager::Update() 40 | { 41 | _it_time += 1.8; 42 | 43 | double dt = _it_time - Time(); 44 | if(dt<-1.79) 45 | { 46 | _lose_tick_cnt++; 47 | _it_time += 1.8; 48 | // com1<<"Lost tick:"<<_lose_tick_cnt<<"\n"; 49 | } 50 | } 51 | 52 | //SysTick interrupt IRQ handler 53 | extern "C" 54 | { 55 | void SysTick_Handler(void) 56 | { 57 | TaskManager::Update(); 58 | } 59 | } 60 | 61 | 62 | -------------------------------------------------------------------------------- /libraries/System/TaskManager/TaskManager.h: -------------------------------------------------------------------------------- 1 | #ifndef _TASK_MANAGER_H_ 2 | #define _TASK_MANAGER_H_ 3 | #include "stm32f10x.h" 4 | 5 | class TaskManager 6 | { 7 | private: 8 | static u16 _lose_tick_cnt; //current updated time 9 | static double _old_time; //last updated time 10 | public: 11 | static double _it_time; //time = SysTick interrupt counter*1.8s 12 | public: 13 | TaskManager(); //constructor 14 | static double Time(); //get current time 15 | static void Update(); 16 | }; 17 | extern TaskManager tskmgr; 18 | 19 | #define MOD_ERROR 0x00 //error 20 | #define MOD_READY 0x01 //ready 21 | #define MOD_BUSY 0x02 //busy 22 | #define MOD_LOCK 0x04 //locked 23 | #define MOD_UNLOCK 0x08 //unlocked 24 | #define MOD_ADJUST 0x10 //adjust, calibrate 25 | 26 | #endif 27 | -------------------------------------------------------------------------------- /libraries/ToolBox/Buffer/FIFOBuffer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/InfiniteYuan/STM32F103DriverLib/fab4f38aa3d24112e14843d503d75923ab37a541/libraries/ToolBox/Buffer/FIFOBuffer.h -------------------------------------------------------------------------------- /libraries/ToolBox/Control/PIDParameter.h: -------------------------------------------------------------------------------- 1 | #ifndef _PID_PARAMETER_H_ 2 | #define _PID_PARAMETER_H_ 3 | 4 | class PIDParameter 5 | { 6 | public: 7 | float Kp; 8 | float Ki; 9 | float Kd; 10 | 11 | float Dt; //control interval, unit s 12 | float thetaI; //the error angle that integrate actived,when greater than this angle, disable integrate 13 | float maxI; //the max control value for integrate 14 | 15 | float _P; 16 | float _I; 17 | float _D; 18 | 19 | float _lstErr; 20 | 21 | float _Derr; 22 | public: 23 | PIDParameter(float kp=0, float ki=0, float kd=0,float dt=0.002, float angleI=5,float satI=5) 24 | { 25 | Kp = kp; 26 | Ki = ki; 27 | Kd = kd; 28 | 29 | Dt = dt; 30 | thetaI = angleI; 31 | maxI = satI; 32 | 33 | _P = 0; 34 | _I = 0; 35 | _D = 0; 36 | _lstErr = 0; 37 | _Derr = 0; 38 | } 39 | void Set_PID(float kp=0, float ki=0, float kd=0) 40 | { 41 | Kp = kp; 42 | Ki = ki; 43 | Kd = kd; 44 | } 45 | void operator()(float kp, float ki, float kd,float dt, float angleI, float satI) 46 | { 47 | Kp = kp; 48 | Ki = ki; 49 | Kd = kd; 50 | 51 | Dt = dt; 52 | thetaI = angleI; 53 | maxI = satI; 54 | } 55 | 56 | float ComputePID(float target, float now) 57 | { 58 | float err = target - now; 59 | 60 | _P = Kp*err; 61 | 62 | float Derr = (err - _lstErr)/Dt; 63 | 64 | _Derr += 0.02*(Derr - _Derr); 65 | 66 | _D = Kd*_Derr; 67 | // _D = Kd * Derr; 68 | 69 | _lstErr = err; 70 | 71 | if(__fabs(err)maxI) _I = maxI; 75 | if(_I<-maxI) _I = -maxI; 76 | } 77 | //else 78 | // _I = 0; 79 | return _P + _D + _I; 80 | } 81 | 82 | }; 83 | 84 | #endif 85 | 86 | 87 | -------------------------------------------------------------------------------- /libraries/ToolBox/GidLink/GidLink.cpp: -------------------------------------------------------------------------------- 1 | #include "GidLink.h" 2 | 3 | 4 | 5 | 6 | UidLink::UidLink(USART &uart):com(uart) 7 | { 8 | 9 | } 10 | 11 | bool UidLink::CheckFrame() 12 | { 13 | 14 | return com.CheckFrame(rxFrame); 15 | } 16 | 17 | bool UidLink::Send() 18 | { 19 | if(!txFrame.isUpdated) //no new frame data, no need to send 20 | return false; 21 | if(!com.SendByte(txFrame.header)) //send frame header 22 | return false; 23 | if(txFrame.fnCode>MAX_FN_CODE || !com.SendByte(txFrame.fnCode)) //send function code 24 | return false; 25 | txFrame.dataLength = DATA_LENGTH[txFrame.fnCode][DIRECTION_SEND]; 26 | if(!com.SendByte(txFrame.dataLength)) //send data length 27 | return false; 28 | if(!com.SendBytes(txFrame.data,txFrame.dataLength)) //send data; 29 | return false; 30 | txFrame.CreateCheckCode(); 31 | if(!com.SendByte(txFrame.checkSum)) //send check code 32 | return false; 33 | txFrame.isUpdated = false; 34 | return true; 35 | } 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /libraries/ToolBox/GidLink/GidLink.h: -------------------------------------------------------------------------------- 1 | #ifndef _UID_LINK_H_ 2 | #define _UID_LINK_H_ 3 | 4 | #include "stm32f10x.h" 5 | #include "FIFOBuffer.h" 6 | #include "USART.h" 7 | 8 | 9 | class UidLink 10 | { 11 | public: 12 | DataFrame txFrame; 13 | DataFrame rxFrame; 14 | USART &com; 15 | public: 16 | UidLink(USART &uart); 17 | bool CheckFrame(); 18 | bool Send(); 19 | }; 20 | 21 | 22 | #endif 23 | 24 | -------------------------------------------------------------------------------- /libraries/ToolBox/Math/AHRS_Quater.h: -------------------------------------------------------------------------------- 1 | #ifndef __AHRS_Quater_H_ 2 | #define __AHRS_Quater_H_ 3 | 4 | #include "Vector3.h" 5 | #include "Matrix3.h" 6 | #include "AHRS.h" 7 | #include "Mathtool.h" 8 | 9 | #define RtA 57.324841f //弧度转化为角度 10 | #define AtR 0.0174533f //角度转化为弧度 11 | 12 | #define so3_comp_params_Kp 1.0f 13 | #define so3_comp_params_Ki 0.05f 14 | 15 | struct MPU6050Filter_tag // IMU滤波后的值 16 | { 17 | Vector3 acc; 18 | Vector3f gyro; 19 | s16 accel_x_f; // ¼ÓËٶȼÆxÂ˲¨ºóµÄÖµ 20 | s16 accel_y_f; // ¼ÓËٶȼÆyÂ˲¨ºóµÄÖµ 21 | s16 accel_z_f; // ¼ÓËٶȼÆzÂ˲¨ºóµÄÖµ 22 | s16 gyro_x_c; // ÍÓÂÝÒDZ궨ºóµÄÖµ 23 | s16 gyro_y_c; // ÍÓÂÝÒDZ궨ºóµÄÖµ 24 | s16 gyro_z_c; // ÍÓÂÝÒDZ궨ºóµÄÖµ 25 | }; 26 | 27 | class AHRS_Quater:public AHRS{ 28 | 29 | private: 30 | 31 | Vector3f mAngle; 32 | Matrix3 mRotateMatrix; 33 | MPU6050Filter_tag g_MPU6050Data_Filter; 34 | float q0, q1, q2 , q3 ; /** quaternion of sensor frame relative to auxiliary frame */ 35 | float dq0, dq1, dq2 , dq3; /** quaternion of sensor frame relative to auxiliary frame */ 36 | float gyro_bias[3]; /** bias estimation */ 37 | float q0q0, q0q1, q0q2, q0q3; 38 | float q1q1, q1q2, q1q3; 39 | float q2q2, q2q3; 40 | float q3q3; 41 | unsigned char bFilterInit; 42 | 43 | public: 44 | AHRS_Quater(InertialSensor &ins,Compass *compass=0, Barometer *baro=0):AHRS(ins,compass,baro) 45 | { 46 | q0 = 1.0f; 47 | gyro_bias[0] = 0.0f; 48 | gyro_bias[1] = 0.0f; 49 | gyro_bias[2] = 0.0f; 50 | } 51 | virtual bool Update(); 52 | virtual bool Ready(); 53 | void IMU_Filter(); 54 | void ToEuler(float *roll, float *pitch, float *yaw) 55 | {//弧度 56 | *pitch = asin(-2 * q1 * q3 + 2 * q0* q2); // pitch * RtA 57 | *roll = atan2(2 * q2 * q3 + 2 * q0 * q1, -2 * q1 * q1 - 2 * q2* q2 + 1); // roll * RtA 58 | *yaw = atan2(2*(q0*q3+q1*q2),1-2*(q2*q2+q3*q3));//yaw * RtA 59 | } 60 | void NonlinearSO3AHRSinit(float ax, float ay, float az, float mx, float my, float mz); 61 | void NonlinearSO3AHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) ; 62 | Vector3f GetAngle(Vector3 acc, Vector3 gyro,float deltaT); 63 | Vector3f GetAngle(Vector3 acc, Vector3 gyro,Vector3 mag,float deltaT); 64 | 65 | }; 66 | 67 | 68 | #endif 69 | -------------------------------------------------------------------------------- /libraries/ToolBox/Math/MathTool.h: -------------------------------------------------------------------------------- 1 | #ifndef _MATH_TOOL_H_ 2 | #define _MATH_TOOL_H_ 3 | 4 | 5 | 6 | #include "Vector3.h" 7 | #include "Quaternion.h" 8 | #include "Matrix3.h" 9 | #include "Vector4.h" 10 | 11 | 12 | #endif 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /libraries/ToolBox/Math/Matrix3.h: -------------------------------------------------------------------------------- 1 | #ifndef _MATRIX3_H_ 2 | #define _MATRIX3_H_ 3 | 4 | #include "Mathtool.h" 5 | #include "Vector3.h" 6 | 7 | template 8 | class Matrix3 9 | { 10 | public: 11 | Vector3 a; //the 1st row 12 | Vector3 b; //the 2nd row 13 | Vector3 c; //the 3rd row 14 | public: 15 | Matrix3() { } //zero the vector elements 16 | Matrix3(const Vector3 &a0, const Vector3 &b0, const Vector3 &c0) : a(a0), b(b0), c(c0) {} 17 | Matrix3(const T ax, const T ay, const T az, const T bx, const T by, const T bz, const T cx, const T cy, const T cz) : a(ax,ay,az), b(bx,by,bz), c(cx,cy,cz) { } 18 | void operator() (const Vector3 &a0, const Vector3 &b0, const Vector3 &c0) {a = a0; b = b0; c = c0; } 19 | bool operator==(const Matrix3 &m) { return (a==m.a && b==m.b && c==m.c); } 20 | bool operator!= (const Matrix3 &m){ return (a!=m.a || b!=m.b || c!=m.c); } 21 | Matrix3 operator-(void) const { return Matrix3(-a,-b,-c); } 22 | Matrix3 operator-(const Matrix3 &m) const { return Matrix3(a-m.a, b-m.b, c-m.c); } 23 | Matrix3 operator+(const Matrix3 &m) const { return Matrix3(a+m.a, b+m.b, c+m.c); } 24 | Matrix3 operator*(const T num) const { return Matrix3(a*num, b*num, c*num); } 25 | Matrix3 operator/(const T num) const { return Matrix3(a/num, b/num, c/num); } 26 | Matrix3 &operator+= (const Matrix3 &m) { return *this = *this + m; } 27 | Matrix3 &operator-= (const Matrix3 &m) { return *this = *this - m; } 28 | Matrix3 &operator*= (const T num) { return *this = *this * num; } 29 | Matrix3 &operator/= (const T num) { return *this = *this / num; } 30 | Vector3 operator *(const Vector3 &v) const { return Vector3(a.x*v.x+a.y*v.y+a.z*v.z, b.x*v.x+b.y*v.y+b.z*v.z, c.x*v.x+c.y*v.y+c.z*v.z); } 31 | Matrix3 operator *(const Matrix3 &m) const 32 | { 33 | Matrix3 temp (Vector3(a.x*m.a.x+a.y*m.b.x+a.z*m.c.x, a.x*m.a.y+a.y*m.b.y+a.z*m.c.y, a.x*m.a.z+a.y*m.b.z+a.z*m.c.z), 34 | Vector3(b.x*m.a.x+b.y*m.b.x+b.z*m.c.x, b.x*m.a.y+b.y*m.b.y+b.z*m.c.y, b.x*m.a.z+b.y*m.b.z+b.z*m.c.z), 35 | Vector3(c.x*m.a.x+c.y*m.b.x+c.z*m.c.x, c.x*m.a.y+c.y*m.b.y+c.z*m.c.y, c.x*m.a.z+c.y*m.b.z+c.z*m.c.z)); 36 | return temp; 37 | } 38 | void Zero(void) { a.x = a.y = a.z = 0; b.x = b.y = b.z = 0; c.x = c.y = c.z = 0; } 39 | void Identity(void) { a.x = b.y = c.z = 1; a.y = a.z = 0; b.x = b.z = 0; c.x = c.y = 0; } 40 | bool IsNan(void) { return a.IsNan() || b.IsNan() || c.IsNan(); } 41 | void Normalize(void) 42 | { 43 | float error = a * b; 44 | Vector3 t0 = a - (b * (0.5f * error)); 45 | Vector3 t1 = b - (a * (0.5f * error)); 46 | Vector3 t2 = t0 % t1; 47 | a = t0 * (1.0f / t0.Length()); 48 | b = t1 * (1.0f / t1.Length()); 49 | c = t2 * (1.0f / t2.Length()); 50 | } 51 | void Rotate(const Vector3 &g) 52 | { 53 | Matrix3 temp_matrix; 54 | temp_matrix.a.x = a.y * g.z - a.z * g.y; 55 | temp_matrix.a.y = a.z * g.x - a.x * g.z; 56 | temp_matrix.a.z = a.x * g.y - a.y * g.x; 57 | temp_matrix.b.x = b.y * g.z - b.z * g.y; 58 | temp_matrix.b.y = b.z * g.x - b.x * g.z; 59 | temp_matrix.b.z = b.x * g.y - b.y * g.x; 60 | temp_matrix.c.x = c.y * g.z - c.z * g.y; 61 | temp_matrix.c.y = c.z * g.x - c.x * g.z; 62 | temp_matrix.c.z = c.x * g.y - c.y * g.x; 63 | (*this) += temp_matrix; 64 | } 65 | Matrix3 Transpose(void) const{ return Matrix3(Vector3(a.x,b.x,c.x), Vector3(a.y,b.y,c.y), Vector3(a.z,b.z,c.z)); } 66 | void ToEuler(float *roll=0, float *pitch=0, float *yaw=0) const 67 | { 68 | if (pitch != 0) { *pitch = -asinf(c.x); } 69 | if (roll != 0) { *roll = atan2f(c.y, c.z); } 70 | if (yaw != 0) { *yaw = atan2f(b.x, a.x); } 71 | } 72 | Vector3 mul_transpose(const Vector3 &v) const 73 | { 74 | return Vector3(a.x * v.x + b.x * v.y + c.x * v.z, 75 | a.y * v.x + b.y * v.y + c.y * v.z, 76 | a.z * v.x + b.z * v.y + c.z * v.z); 77 | } 78 | }; 79 | 80 | 81 | #endif 82 | 83 | 84 | -------------------------------------------------------------------------------- /libraries/ToolBox/Math/Quaternion.cpp: -------------------------------------------------------------------------------- 1 | 2 | -------------------------------------------------------------------------------- /libraries/ToolBox/Math/Quaternion.h: -------------------------------------------------------------------------------- 1 | #ifndef _QUATERNION_H_ 2 | #define _QUATERNION_H_ 3 | 4 | #include "math.h" 5 | 6 | class Quaternion 7 | { 8 | public: 9 | float q1, q2, q3, q4; 10 | public: 11 | // constructor creates a quaternion equivalent to roll=0, pitch=0, yaw=0 12 | Quaternion() { q1 = 1; q2 = q3 = q4 = 0; } 13 | // setting constructor 14 | Quaternion(float _q1, float _q2, float _q3, float _q4):q1(_q1), q2(_q2), q3(_q3), q4(_q4) {} 15 | // function call operator 16 | void operator()(float _q1, float _q2, float _q3, float _q4) {q1 = _q1; q2 = _q2; q3 = _q3; q4 = _q4; } 17 | // check if any elements are NAN 18 | bool IsNan(void) { return isnan(q1) || isnan(q2) || isnan(q3) || isnan(q4); } 19 | // create eulers from a quaternion 20 | void ToEuler(float &roll, float &pitch, float &yaw) 21 | { 22 | roll = atan2(2.0*(q1*q2 + q3*q4), 1 - 2.0*(q2*q2 + q3*q3)); 23 | pitch = asin(2.0*(q1*q3 - q4*q2)); 24 | yaw = atan2(2.0*(q1*q4 + q2*q3), 1 - 2.0*(q3*q3 + q4*q4)); 25 | } 26 | }; 27 | #endif // QUATERNION_H 28 | -------------------------------------------------------------------------------- /libraries/ToolBox/Math/Vector3.h: -------------------------------------------------------------------------------- 1 | #ifndef _VECTOR3_H_ 2 | #define _VECTOR3_H_ 3 | 4 | #include "math.h" 5 | 6 | template 7 | class Vector3 8 | { 9 | public: 10 | T x,y,z; 11 | public: 12 | //defualt constructor 13 | Vector3() { x = 0; y = 0; z = 0; } 14 | // setting ctor 15 | Vector3(T x0, T y0, T z0) : x(x0), y(y0), z(z0) {} 16 | //"()" overload 17 | void operator()(T x0, T y0, T z0){x= x0; y= y0; z= z0;} 18 | //"==" overload 19 | bool operator==(const Vector3 &v){return (x==v.x && y==v.y && z==v.z); } 20 | //"!=" overload 21 | bool operator!=(const Vector3 &v){return (x!=v.x || y!=v.y || z!=v.z); } 22 | // "-" negation overload 23 | Vector3 operator-(void) const { return Vector3(-x,-y,-z);} 24 | //"+" addition overload 25 | Vector3 operator+(const Vector3 &v) const { return Vector3(x+v.x, y+v.y, z+v.z); } 26 | //"-" subtraction overload 27 | Vector3 operator-(const Vector3 &v) const { return Vector3(x-v.x, y-v.y, z-v.z); } 28 | //"*" multiply overload 29 | Vector3 operator*(const T n)const { return Vector3(x*n, y*n, z*n); } 30 | //"/" divsion overload 31 | Vector3 operator/(const T n)const { return Vector3(x/n, y/n, z/n); } 32 | //"+=" overload 33 | Vector3 &operator+=(const Vector3 &v) { x+=v.x; y+=v.y; z+=v.z; return *this; } 34 | //"-=" overload 35 | Vector3 &operator-=(const Vector3 &v) { x-=v.x; y-=v.y; z-=v.z; return *this; } 36 | //"*=" overload 37 | Vector3 &operator*=(const T n) { x*=n; y*=n; z*=n; return *this; } 38 | // uniform scaling 39 | Vector3 &operator/=(const T n) { x/=n; y/=n; z/=n; return *this; } 40 | //dot product 41 | T operator*(const Vector3 &v) const { return x*v.x + y*v.y + z*v.z; } 42 | //cross product 43 | Vector3 operator %(const Vector3 &v)const { return Vector3(y*v.z-z*v.y, z*v.x-x*v.z, x*v.y-y*v.x);} 44 | // gets the length of this vector squared 45 | T LengthSquared() const { return (T)(*this * *this); } 46 | // gets the length of this vector 47 | float Length(void) const { return (T)sqrt(*this * *this); } 48 | // normalizes this vector 49 | void Normalize() { *this/=Length(); } 50 | // zero the vector 51 | void Zero() { x = y = z = 0.0; } 52 | // returns the normalized version of this vector 53 | Vector3 Normalized() const { return *this/Length(); } 54 | // check if any elements are NAN 55 | bool IsNan(void) { return isnan(x) || isnan(y) || isnan(z); } 56 | // check if any elements are infinity 57 | bool IsInf(void) { return isinf(x) || isinf(y) || isinf(z); } 58 | 59 | }; 60 | typedef Vector3 Vector3f; 61 | #endif // VECTOR3_H 62 | -------------------------------------------------------------------------------- /libraries/ToolBox/Math/Vector4.h: -------------------------------------------------------------------------------- 1 | #ifndef _VECTOR4_H_ 2 | #define _VECTOR4_H_ 3 | 4 | 5 | 6 | class CraftVector 7 | { 8 | public: 9 | float roll; 10 | float pitch; 11 | float yaw; 12 | float throttle; 13 | public: 14 | CraftVector() {roll=0; pitch=0; yaw=0; throttle=0; } 15 | void operator()(float r,float p,float y,float t){ roll=r; pitch=p; yaw=y; throttle=t;} 16 | }; 17 | 18 | 19 | #endif 20 | 21 | 22 | --------------------------------------------------------------------------------