├── .gitignore ├── simulate.sh ├── .gitmodules ├── ExtraFunctions.h ├── Integrator.cpp ├── makefile ├── MotorController.h ├── Sensors ├── DataWXYZ.cpp ├── Coordinate.cpp ├── SensorIMU.cpp ├── SensorGPS.cpp ├── SensorAccelerometer.cpp ├── SensorConvertion.h ├── SensorIMU.h ├── SensorGPS.h ├── SensorAccelerometer.h ├── DataWXYZ.h ├── Coordinate.h ├── SensorConvertion.cpp ├── SensorThreading.h ├── SensorThreading.cpp ├── Backup ├── bricklet_accelerometer.h ├── bricklet_gps.h ├── ip_connection.h ├── bricklet_accelerometer.cpp ├── bricklet_gps.cpp └── brick_imu_v2.h ├── README.md ├── FlowRegDefine.h ├── Integrator.h ├── MotorController.cpp ├── SensorCalculations.h ├── Simulate.h ├── PhysicalDefinitions.h ├── SensorCalculations.cpp ├── viewSimulation.py ├── PIDController.cpp ├── PIDController.h ├── BoatController.h ├── Simulate.cpp ├── main.cpp ├── BoatController.cpp └── LICENCE /.gitignore: -------------------------------------------------------------------------------- 1 | *.o 2 | prog 3 | .vscode* 4 | compileAndRun 5 | doxygen_output/ 6 | *.csv 7 | -------------------------------------------------------------------------------- /simulate.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | make 3 | 4 | ./prog > data.csv 5 | 6 | python viewSimulation.py 7 | -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "Vector2"] 2 | path = Vector2 3 | url = https://github.com/overlord1123/Vector2.git 4 | [submodule "FlowSerial"] 5 | path = FlowSerial 6 | url = https://github.com/overlord1123/FlowSerial.git 7 | -------------------------------------------------------------------------------- /ExtraFunctions.h: -------------------------------------------------------------------------------- 1 | #ifndef _EXTRAFUNCTIONS_H_ 2 | #define _EXTRAFUNCTIONS_H_ 3 | 4 | template const T& limit (const T& val, const T& min, const T& max){ 5 | return (val < min) ? min : ((val > max) ? max : val); 6 | } 7 | #endif 8 | -------------------------------------------------------------------------------- /Integrator.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "Integrator.h" 3 | 4 | Integrator::Integrator(float idT): 5 | dT(idT){} 6 | 7 | Integrator::Integrator(float idT, float iy): 8 | dT(idT), 9 | y(iy){} 10 | 11 | float Integrator::update(float input){ 12 | return y = y + ((input + x_1) * dT / 2); 13 | } 14 | -------------------------------------------------------------------------------- /makefile: -------------------------------------------------------------------------------- 1 | CXX=g++ 2 | CXXFLAGS=-g -std=c++11 -Wall -pedantic 3 | LINKFLAGS=-pthread 4 | BIN=prog 5 | 6 | SRC=$(wildcard *.cpp) $(wildcard */*.cpp) 7 | OBJ=$(SRC:%.cpp=%.o) 8 | 9 | all: $(OBJ) 10 | $(CXX) $(LINKFLAGS) -o $(BIN) $^ 11 | 12 | %.o: %.c 13 | $(CXX) $@ -c $< 14 | 15 | clean: 16 | rm -f *.o */*.o 17 | rm $(BIN) 18 | -------------------------------------------------------------------------------- /MotorController.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef _MOTORCOLTROLLER_H_ 3 | #define _MOTORCOLTROLLER_H_ 4 | 5 | #include "FlowRegDefine.h" 6 | #include "FlowSerial/FlowSerial.hpp" 7 | 8 | class MotorController: public FlowRegDefine{ 9 | public: 10 | MotorController(FlowSerial::UsbSocket& iflowSerialInterface); 11 | ~MotorController(); 12 | void startMotors(); 13 | void syncRegisters(); 14 | private: 15 | FlowSerial::UsbSocket& flowSerialInterface; 16 | }; 17 | 18 | #endif 19 | -------------------------------------------------------------------------------- /Sensors/DataWXYZ.cpp: -------------------------------------------------------------------------------- 1 | #include "DataWXYZ.h" 2 | 3 | DataWXYZ::DataWXYZ(float wVal, float xVal, float yVal, float zVal){ 4 | w = wVal; 5 | x = xVal; 6 | y = yVal; 7 | z = zVal; 8 | } 9 | DataWXYZ::DataWXYZ(){} 10 | DataWXYZ::~DataWXYZ(){} 11 | 12 | float DataWXYZ::getW(){return w;} 13 | 14 | float DataWXYZ::getX(){return x;} 15 | 16 | float DataWXYZ::getY(){return y;} 17 | 18 | float DataWXYZ::getZ() {return z;} 19 | 20 | void DataWXYZ::printData(){ 21 | printf("w: %.2f, x: %.2f, y: %.2f, z: %.2f\n", 22 | w, x, y, z); 23 | } -------------------------------------------------------------------------------- /Sensors/Coordinate.cpp: -------------------------------------------------------------------------------- 1 | #include "Coordinate.h" 2 | 3 | Coordinate::Coordinate(uint32_t iLatitude, uint32_t iLongitude, char cNs, char cEw){ 4 | longitude = iLongitude; 5 | latitude = iLatitude; 6 | ns = cNs; 7 | ew = cEw; 8 | } 9 | Coordinate::~Coordinate(){} 10 | Coordinate::Coordinate(){} 11 | float Coordinate::getLongitude(){ 12 | return longitude; 13 | } 14 | float Coordinate::getLatitude(){ 15 | return latitude; 16 | } 17 | char Coordinate::getEW(){ 18 | return ew; 19 | } 20 | char Coordinate::getNS(){ 21 | return ns; 22 | } 23 | void Coordinate::printLongLat(){ 24 | printf("Latitude: %f° %c\n", latitude/1000000.0, ns); 25 | printf("Longitude: %f° %c\n", longitude/1000000.0, ew); 26 | } -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Dynamic-positioning 2 | Build for RH marine. The students of the Hague university made a dynamic positioning system that can be implemented an a Raspberry Pi or any other Linux based computer 3 | ## Type of boat 4 | This software currently only works with a boat with two azimuth thruster in the front and back. 5 | If you want to use this software on other types of boats you must change the boatController.cpp and .h files. 6 | ## Dependicies 7 | Note that this software works in combination with a Arduino board with motors installed on them. 8 | The software for the arduino can be found [here](https://github.com/overlord1123/Dynamic-positioning-arduino/). 9 | Also the Arduino itself uses the FlowSerial library. This can be found [here](https://github.com/overlord1123/FlowSerialArduino) 10 | -------------------------------------------------------------------------------- /FlowRegDefine.h: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | class FlowRegDefine{ 5 | public: 6 | FlowRegDefine(){flowReg[0] = 0; flowReg[1] = 0;} 7 | uint8_t flowReg[4]; 8 | static const size_t flowRegSize = sizeof(flowReg) / sizeof(flowReg[0]); 9 | inline uint8_t getMotorFront(){return flowReg[0];} 10 | inline void setMotorFront(uint8_t motorFront){flowReg[0] = motorFront;} 11 | inline uint8_t getMotorBack(){return flowReg[1];} 12 | inline void setMotorBack(uint8_t motorBack){flowReg[1] = motorBack;} 13 | inline uint8_t getRotationFront(){return flowReg[2];} 14 | inline void setRotationFront(uint8_t rotationFront){flowReg[2] = rotationFront;} 15 | inline uint8_t getRotationBack(){return flowReg[3];} 16 | inline void setRotationBack(uint8_t rotationBack){flowReg[3] = rotationBack;} 17 | }; 18 | -------------------------------------------------------------------------------- /Integrator.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef _INTEGRATOR_H_ 3 | #define _INTEGRATOR_H_ 4 | 5 | class Integrator 6 | { 7 | public: 8 | Integrator(float idT); 9 | Integrator(float idT, float iy); 10 | /** 11 | * @brief Update funtion to insert new value. 12 | * @details This functionality was discovered using the 13 | * billiniear transform on H(s)=1/s. 14 | * 15 | * @param input Input value used to integrate. 16 | * @return Newly calculated output value. 17 | */ 18 | float update(float input); 19 | /** 20 | * @return Current output value of the integrator. 21 | */ 22 | float getCurrentOutput(){return y;} 23 | const float dT; 24 | private: 25 | Integrator(); 26 | float y = 0; /**< current output value. Also used as previous output value */ 27 | float x_1 = 0; /**< Previous input value */ 28 | }; 29 | 30 | #endif //_INTEGRATOR_H_ 31 | -------------------------------------------------------------------------------- /Sensors/SensorIMU.cpp: -------------------------------------------------------------------------------- 1 | #include "SensorIMU.h" 2 | 3 | void SensorIMU::create(){ 4 | ipcon_create(&ipcon); 5 | imu_v2_create(&imu, IMUUID, &ipcon); 6 | } 7 | 8 | void SensorIMU::destroy(){ 9 | imu_v2_destroy(&imu); 10 | ipcon_destroy(&ipcon); 11 | } 12 | 13 | float SensorIMU::connect(){ 14 | if(ipcon_connect(&ipcon, HOST, PORT) < 0) { 15 | fprintf(stderr, "Could not connect\n"); 16 | return 1; 17 | } 18 | return 0; 19 | } 20 | 21 | float SensorIMU::determineQuaternion(){ 22 | if(imu_v2_get_quaternion(&imu, &w, &x, &y, &z) < 0) { 23 | fprintf(stderr, "Could not get quaternion, probably timeout\n"); 24 | return 1; 25 | } 26 | dataWXYZ = DataWXYZ(w / 16383.0, x / 16383.0, y / 16383.0, z / 16383.0); 27 | return 0; 28 | } 29 | 30 | DataWXYZ SensorIMU::getQuaternion(){ 31 | return dataWXYZ;} -------------------------------------------------------------------------------- /Sensors/SensorGPS.cpp: -------------------------------------------------------------------------------- 1 | #include "SensorGPS.h" 2 | 3 | void SensorGPS::create(){ 4 | ipcon_create(&ipcon); 5 | gps_create(&gps, GPSUID, &ipcon); 6 | } 7 | float SensorGPS::connect(){ 8 | if(ipcon_connect(&ipcon, HOST, PORT) < 0) { 9 | fprintf(stderr, "Could not connect\n"); 10 | return 1; 11 | } 12 | return 0; 13 | } 14 | 15 | void SensorGPS::destroy(){ 16 | gps_destroy(&gps); 17 | ipcon_destroy(&ipcon); 18 | } 19 | 20 | float SensorGPS::determineCoordinates(){ 21 | if(gps_get_coordinates(&gps, &latitude, &ns, &longitude, &ew, &pdop, &hdop, &vdop, 22 | &epe) < 0) { 23 | fprintf(stderr, "Could not get coordinates, probably timeout\n"); 24 | return 1; 25 | } 26 | coordinate = Coordinate(latitude, longitude, ns, ew); 27 | return 0; 28 | } 29 | Coordinate SensorGPS::getCoordinate(){ 30 | return coordinate; 31 | } 32 | -------------------------------------------------------------------------------- /MotorController.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include //For usleep specific for this example 3 | #include "MotorController.h" 4 | 5 | MotorController::MotorController(FlowSerial::UsbSocket& iflowSerialInterface): 6 | flowSerialInterface(iflowSerialInterface) 7 | { 8 | flowSerialInterface.startUpdateThread(); 9 | setMotorFront(0); 10 | setMotorBack(0); 11 | setRotationFront(90); 12 | setRotationBack(90); 13 | syncRegisters(); 14 | } 15 | 16 | MotorController::~MotorController(){ 17 | setMotorFront(36); 18 | setMotorBack(36); 19 | syncRegisters(); 20 | } 21 | 22 | void MotorController::startMotors(){ 23 | setMotorFront(180); 24 | setMotorBack(180); 25 | syncRegisters(); 26 | usleep(3000000); 27 | 28 | setMotorFront(30); 29 | setMotorBack(30); 30 | syncRegisters(); 31 | usleep(3000000); 32 | } 33 | 34 | void MotorController::syncRegisters(){ 35 | flowSerialInterface.writeToPeer(0, flowReg, flowRegSize); 36 | } 37 | -------------------------------------------------------------------------------- /SensorCalculations.h: -------------------------------------------------------------------------------- 1 | #ifndef _SensorCalculations_H_ 2 | #define _SensorCalculations_H_ 3 | #define false 0 4 | #define true 1 5 | #include 6 | #include "Vector2/Vector2.hpp" 7 | 8 | //kalman 9 | //Prediction Speed, 10 | //Lastspeed + time * Acceleration 11 | // 12 | //Predictment Position X,Y 13 | //LastMesurement + (Speed * time) * lastspeed + 0.5 * acceleration * speed * (time* time) 14 | class SensorCalculations 15 | { 16 | public: 17 | //Calcualtes currentSpeed. 18 | //Uses speed, accelerationsensor, Heading. 19 | void predictSpeed(Vector2 speed, float time, float acceleration); 20 | 21 | void predictNextLocation(Vector2 setpointPosition, Vector2 speed, float timePeriod, float acceleration); 22 | 23 | Vector2 getSpeed(); 24 | float getHeading(); 25 | 26 | private: 27 | Vector2 predictedLocation[10]; 28 | Vector2 predictedSpeed[10]; 29 | float heading = 0; 30 | Vector2 speed = 0; 31 | Vector2 currentPosition = 0; 32 | }; 33 | 34 | #endif 35 | -------------------------------------------------------------------------------- /Simulate.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef _SIMULATE_H_ 3 | #define _SIMULATE_H_ 4 | 5 | #include "Vector2/Vector2.hpp" 6 | #include "PhysicalDefinitions.h" 7 | 8 | class SimulatedWorld{ 9 | public: 10 | /** 11 | * @brief Constructor to set the pointer to boat and configuring delta time of the simulation. 12 | * @details [long description] 13 | * 14 | * @param iboat pointer to phisical boat object. Here data will be overwritten about its current location and speed. 15 | * Throttle data is used to simulate the acceleration 16 | * @param idT Delta time for every simulation cycle. 17 | */ 18 | SimulatedWorld(Boat* iboat, float idT); 19 | /** 20 | * @brief Do a calulation cyle on the boat 21 | * @details Every time this function is called the boat will be simulated by dT time forward. 22 | */ 23 | void calculateWorldTick(); 24 | private: 25 | Boat* boat; /**< pointer to boat. The truster data will be read and the postion and heading data will be writen by this class */ 26 | const float dT; /**< period time for each calculation cycle */ 27 | }; 28 | 29 | #endif //_SIMULATE_H_ 30 | -------------------------------------------------------------------------------- /Sensors/SensorAccelerometer.cpp: -------------------------------------------------------------------------------- 1 | #include "SensorAccelerometer.h" 2 | 3 | void SensorAccelerometer::create(){ 4 | ipcon_create(&ipcon); 5 | accelerometer_create(&a, ACCELEROUID, &ipcon); 6 | } 7 | float SensorAccelerometer::connect(){ 8 | if(ipcon_connect(&ipcon, HOST, PORT) < 0) { 9 | fprintf(stderr, "Could not connect\n"); 10 | return 1; 11 | } 12 | return 0; 13 | } 14 | 15 | void SensorAccelerometer::destroy(){ 16 | accelerometer_destroy(&a); 17 | ipcon_destroy(&ipcon); 18 | } 19 | 20 | float SensorAccelerometer::determineAcceleration(){ 21 | if(accelerometer_get_acceleration(&a, &x, &y, &z) < 0) { 22 | fprintf(stderr, "Could not get acceleration, probably timeout\n"); 23 | return 1; 24 | } 25 | dataWXYZ = DataWXYZ(0, x / 16383.0, y / 16383.0, z / 16383.0); 26 | return 0; 27 | } 28 | void SensorAccelerometer::printXYZ(){ 29 | printf("Acceleration[X]: %f g\n", x/1000.0); 30 | printf("Acceleration[Y]: %f g\n", y/1000.0); 31 | printf("Acceleration[Z]: %f g\n", z/1000.0); 32 | } 33 | DataWXYZ SensorAccelerometer::getAcceleration(){ 34 | return dataWXYZ; 35 | } 36 | -------------------------------------------------------------------------------- /Sensors/SensorConvertion.h: -------------------------------------------------------------------------------- 1 | #ifndef _SensorConvertion_H_ 2 | #define _SensorConvertion_H_ 3 | 4 | 5 | #include "SensorThreading.h" 6 | #include "Coordinate.h" 7 | #include "DataWXYZ.h" 8 | 9 | #include 10 | #include 11 | #include 12 | #include 13 | 14 | /** 15 | * @brief Class for sensor convertion. 16 | */ 17 | class SensorConvertion 18 | { 19 | public: 20 | /** 21 | * @brief Constructor 22 | */ 23 | SensorConvertion(); 24 | /** 25 | * @brief Destroys the object. 26 | */ 27 | ~SensorConvertion(); 28 | 29 | //Long lat convertion 30 | 31 | /** 32 | * @brief Long lat convertion 33 | * 34 | * @return Long lat in xyz 35 | */ 36 | DataWXYZ longLatToXYZ(); 37 | /** 38 | * @brief Rotation convertion 39 | * 40 | * @param location The location 41 | * 42 | * @return corrected location by using IMU data 43 | */ 44 | DataWXYZ convertIMUValues(DataWXYZ *location); 45 | 46 | private: 47 | // long lat convertion 48 | float rad = 6378137.0; 49 | float f = 1.0 / 298.257224; 50 | 51 | DataWXYZ lastCalculation; 52 | DataWXYZ lastGPSposition; 53 | }; 54 | 55 | #endif 56 | -------------------------------------------------------------------------------- /PhysicalDefinitions.h: -------------------------------------------------------------------------------- 1 | #ifndef _PHYSICALDEFINITIONS_H_ 2 | #define _PHYSICALDEFINITIONS_H_ 3 | 4 | #include "PIDController.h" 5 | #include "SensorCalculations.h" 6 | 7 | //Al units are in basic SI units. m, kg, s etc. unless other specified 8 | 9 | #include "Vector2/Vector2.hpp" 10 | 11 | class BaseThurster{ 12 | public: 13 | Vector2 localLocation; 14 | float normalRotation = 0; 15 | float throttle = 0; 16 | float maxForce = 0; 17 | }; 18 | 19 | class AzimuthThruster: public BaseThurster{ 20 | public: 21 | float rotation = 0; 22 | }; 23 | 24 | class Boat{ 25 | public: 26 | AzimuthThruster azimuthThruster[2]; 27 | //Positional states 28 | //SensorCalculations sensorCalculations; 29 | Vector2 currentPosition = 0; //Current position of the boat (in X,Y). 30 | Vector2 currentSpeed = 0; //Current speed of the boat (in X,Y). 31 | float setpointSpeed = 0; //The maximal speed you want (user input). 32 | Vector2 setpointPosition = 0; //The position the boat is heading to. 33 | float currentHeading = 0, setpointHeading = 0; //Heading is the amount of radians. 34 | float currentBoatAngularSpeed = 0; //How fast the ship is turning is radians per second = 2 * pi * f 35 | //Physical properies 36 | float mass; 37 | float angularMass; 38 | Vector2 directionalDamping = 0; 39 | float angularDamping = 0; 40 | }; 41 | #endif 42 | -------------------------------------------------------------------------------- /SensorCalculations.cpp: -------------------------------------------------------------------------------- 1 | #include "SensorCalculations.h" 2 | 3 | //Predictment Position X,Y 4 | //LastMesurement + (Speed * time) * lastspeed + 0.5 * acceleration * speed * (time* time) 5 | 6 | void SensorCalculations::predictSpeed(Vector2 speed, float timePeriod, float acceleration) 7 | { 8 | predictedSpeed[0] = speed; 9 | 10 | for (int i = 1; i < 10; i++) 11 | { 12 | predictedSpeed[i].x = predictedSpeed[i - 1].x + (timePeriod * acceleration); 13 | predictedSpeed[i].y = predictedSpeed[i - 1].y + (timePeriod * acceleration); 14 | } 15 | } 16 | //Predictment Position X,Y 17 | //LastMesurement + (Speed * time) * lastspeed + 0.5 * acceleration * speed * (time* time) 18 | void SensorCalculations::predictNextLocation(Vector2 setpointPosition, Vector2 speed, float timePeriod, float acceleration) 19 | { 20 | predictedLocation[0] = setpointPosition; 21 | 22 | for (int i = 1; i < 10; i++) 23 | { 24 | predictedLocation[i].x = predictedLocation[i - 1].x + (predictedSpeed[i].x * timePeriod) * predictedSpeed[i - 1].x + 25 | 0.5 * acceleration * predictedSpeed[i].x * (timePeriod * timePeriod); 26 | predictedLocation[i].y = predictedLocation[i - 1].y + (predictedSpeed[i].y * timePeriod) * predictedSpeed[i - 1].y + 27 | 0.5 * acceleration * predictedSpeed[i].y * (timePeriod * timePeriod); 28 | } 29 | } -------------------------------------------------------------------------------- /Sensors/SensorIMU.h: -------------------------------------------------------------------------------- 1 | #ifndef _SensorIMU_H_ 2 | #define _SensorIMU_H_ 3 | 4 | #include "../PhysicalDefinitions.h" 5 | #include "DataWXYZ.h" 6 | #include "ip_connection.h" 7 | #include "brick_imu_v2.h" 8 | 9 | /** 10 | * Defines hostname 11 | */ 12 | #define HOST "localhost" 13 | /** 14 | * Defines used port number 15 | */ 16 | #define PORT 4223 17 | /** 18 | * Defines IMUUID for current sensor 19 | */ 20 | #define IMUUID "5VGPJ3" // Change XYZ to the UID of your Bricklet 21 | 22 | /** 23 | * @brief Class for sensor imu. 24 | */ 25 | class SensorIMU{ 26 | public: 27 | /** 28 | * @brief Create IP connection and device object 29 | */ 30 | void create(); 31 | 32 | /** 33 | * @brief Calls ipcon_disconnect internally and destroys IMU-object 34 | */ 35 | void destroy(); 36 | 37 | /** 38 | * @brief Connect to brickd, ipcon 39 | * 40 | * @return 0 for success 41 | */ 42 | float connect(); 43 | 44 | /** 45 | * @brief Don't use device before ipcon is connected!! Determine 46 | * Quaternion 47 | * 48 | * @return 0 for succes 49 | */ 50 | float determineQuaternion(); 51 | 52 | /** 53 | * @brief Gets the quaternion. 54 | * 55 | * @return The quaternion. 56 | */ 57 | DataWXYZ getQuaternion(); 58 | 59 | private: 60 | IPConnection ipcon; 61 | IMUV2 imu; 62 | DataWXYZ dataWXYZ; 63 | int16_t w, x, y, z; 64 | }; 65 | #endif 66 | -------------------------------------------------------------------------------- /Sensors/SensorGPS.h: -------------------------------------------------------------------------------- 1 | #ifndef _SensorGPS_H_ 2 | #define _SensorGPS_H_ 3 | 4 | #include "../PhysicalDefinitions.h" 5 | #include "Coordinate.h" 6 | #include "ip_connection.h" 7 | #include "bricklet_gps.h" 8 | 9 | /** 10 | * Defines hostname 11 | */ 12 | #define HOST "localhost" 13 | /** 14 | * Defines used port 15 | */ 16 | #define PORT 4223 17 | /** 18 | * Define GPSUID for current GPS sensor 19 | */ 20 | #define GPSUID "svS" // Change XYZ to the UID of your Bricklet 21 | 22 | /** 23 | * @brief Class for sensor gps. 24 | */ 25 | class SensorGPS{ 26 | public: 27 | /** 28 | * @brief Create IP connection and device object 29 | */ 30 | void create(); 31 | /** 32 | * @brief Calls ipcon_disconnect internally and destroys gps-object 33 | */ 34 | void destroy(); 35 | 36 | /** 37 | * @brief Connect to brickd, ipcon 38 | * 39 | * @return 0 for succes 40 | */ 41 | float connect(); 42 | 43 | /** 44 | * @brief !!Don't use device before ipcon is connected!! determines 45 | * current coordinates 46 | * 47 | * @return 0 for succes 48 | */ 49 | float determineCoordinates(); 50 | 51 | /** 52 | * @brief Gets the coordinate. 53 | * 54 | * @return The coordinate. 55 | */ 56 | Coordinate getCoordinate(); 57 | 58 | private: 59 | IPConnection ipcon; 60 | Coordinate coordinate; 61 | GPS gps; 62 | uint32_t latitude, longitude; 63 | uint16_t pdop, hdop, vdop, epe; 64 | char ns, ew; 65 | }; 66 | 67 | #endif 68 | -------------------------------------------------------------------------------- /Sensors/SensorAccelerometer.h: -------------------------------------------------------------------------------- 1 | #ifndef _SensorAccelerometer_H_ 2 | #define _SensorAccelerometer_H_ 3 | 4 | #include "../PhysicalDefinitions.h" 5 | #include "ip_connection.h" 6 | #include "bricklet_accelerometer.h" 7 | #include "DataWXYZ.h" 8 | 9 | /** 10 | * define host name 11 | */ 12 | #define HOST "localhost" 13 | /** 14 | * define used port number 15 | */ 16 | #define PORT 4223 17 | /** 18 | * Change XYZ to the UID of your Bricklet 19 | */ 20 | #define ACCELEROUID "5VGPJ3" 21 | 22 | /** 23 | * @brief Class for sensor accelerometer. 24 | */ 25 | class SensorAccelerometer{ 26 | public: 27 | /** 28 | * @brief Create IP connection and device object 29 | */ 30 | void create(); 31 | 32 | /** 33 | * @brief Calls ipcon_disconnect internally and destroys gps-object 34 | */ 35 | void destroy(); 36 | 37 | /** 38 | * @brief Connect to brickd, ipcon 39 | * 40 | * @return 0 for success 41 | */ 42 | float connect(); 43 | 44 | /** 45 | * @brief !!Don't use device before ipcon is connected!! determines // 46 | * current acceleration (unit is g/1000) 47 | * 48 | * @return 0 for succes 49 | */ 50 | float determineAcceleration(); 51 | 52 | /** 53 | * @brief prints data 54 | */ 55 | void printXYZ(); 56 | /** 57 | * @brief Gets the acceleration. 58 | * 59 | * @return The acceleration. 60 | */ 61 | DataWXYZ getAcceleration(); 62 | 63 | private: 64 | IPConnection ipcon; 65 | DataWXYZ dataWXYZ; 66 | Accelerometer a; 67 | int16_t x, y, z; 68 | }; 69 | 70 | #endif 71 | -------------------------------------------------------------------------------- /viewSimulation.py: -------------------------------------------------------------------------------- 1 | import csv 2 | import numpy as np 3 | import matplotlib.pyplot as plt 4 | 5 | f = open('data.csv', 'rb') 6 | reader = csv.reader(f, delimiter=',') 7 | headers = reader.next() 8 | 9 | data = {} 10 | 11 | for h in headers: 12 | data[h] = [] 13 | 14 | for row in reader: 15 | for h, v in zip(headers,row): 16 | data[h].append(np.float(v)) 17 | 18 | plt.figure(1) 19 | plt.subplot(221) 20 | plt.legend(plt.plot(data['time'], data['x'], 'r', 21 | data['time'], data['y'], 'g', 22 | data['time'], data['heading'], 'b'), 23 | ['x', 'y', 'heading']) 24 | plt.axhline(0, color='black') 25 | 26 | plt.subplot(222) 27 | plt.legend(plt.plot(data['time'], data['thruster0rotation'], 'g', 28 | data['time'], data['thruster1rotation'], 'y', 29 | data['time'], data['thrust0'], 'b', 30 | data['time'], data['thrust1'], 'r'), 31 | ["thrust0rot", "thrust1rot", "thrust0", "thrust1"]) 32 | plt.axhline(0, color='black') 33 | 34 | plt.subplot(223) 35 | plt.legend(plt.plot(data['time'], data['xSignal'], 'r', 36 | data['time'], data['ySignal'], 'g', 37 | data['time'], data['hSignal'], 'b'), 38 | ['xSignal', 'ySignal', "hSignal"]) 39 | plt.axhline(0, color='black') 40 | 41 | plt.subplot(224) 42 | plt.legend(plt.plot(data['time'], data['errorX'], 'r', 43 | data['time'], data['errorY'], 'g', 44 | data['time'], data['errorH'], 'b'), 45 | ["errorX", "errorY", "errorH"]) 46 | plt.axhline(0, color='black') 47 | 48 | plt.show() 49 | -------------------------------------------------------------------------------- /Sensors/DataWXYZ.h: -------------------------------------------------------------------------------- 1 | #ifndef _DataWXYZ_H_ 2 | #define _DataWXYZ_H_ 3 | 4 | #include 5 | 6 | /** 7 | * @brief Class for data wxyz. These are quaternion numbers for the Gyro data. 8 | */ 9 | class DataWXYZ{ 10 | public: 11 | /** 12 | * @brief Constructor 13 | * 14 | * @param[in] wVal The w value 15 | * @param[in] xVal The x value 16 | * @param[in] yVal The y value 17 | * @param[in] zVal The z value 18 | */ 19 | DataWXYZ(float wVal, float xVal, float yVal, float zVal); 20 | /** 21 | * @brief Empty constructor 22 | */ 23 | DataWXYZ(); 24 | /** 25 | * @brief Destroys the object. 26 | */ 27 | ~DataWXYZ(); 28 | 29 | //functions 30 | 31 | 32 | /** 33 | * @brief Gets the w. 34 | * 35 | * @return The w. 36 | */ 37 | float getW(); 38 | 39 | /** 40 | * @brief Gets the x. 41 | * 42 | * @return The x. 43 | */ 44 | float getX(); 45 | 46 | /** 47 | * @brief Gets the y. 48 | * 49 | * @return The y. 50 | */ 51 | float getY(); 52 | 53 | /** 54 | * @brief Gets the z. 55 | * 56 | * @return The z. 57 | */ 58 | float getZ(); 59 | 60 | /** 61 | * @brief Prints the data to the terminal 62 | */ 63 | void printData(); 64 | 65 | private: 66 | //variables 67 | float w, x, y, z; 68 | }; 69 | #endif 70 | -------------------------------------------------------------------------------- /PIDController.cpp: -------------------------------------------------------------------------------- 1 | //This file contains the code of the PIDController class 2 | #include "PIDController.h" 3 | #include 4 | 5 | 6 | PIDController::PIDController(): 7 | PIDController( 8 | 0.0, 9 | 0.0, 10 | 0.0, 11 | 0.0, 12 | 0.0, 13 | 1.0, 14 | std::chrono::duration(std::chrono::duration_values::zero())){} 15 | 16 | PIDController::PIDController(float p, float i, float d, float prev, float integral, float iGain): 17 | PIDController(p, i, d, prev, integral, iGain, std::chrono::duration(std::chrono::duration_values::zero())){} 18 | 19 | PIDController::PIDController(float p, float i, float d, float prev, float integral, float iGain, std::chrono::duration sampleTime): 20 | Kp(p), 21 | Ki(i), 22 | Kd(d), 23 | inputGain(iGain), 24 | dT(sampleTime), 25 | ePrevious(prev), 26 | eIntegral(integral){} 27 | 28 | PIDController::~PIDController(){} 29 | 30 | float PIDController::calculateOutput(float eInput){ 31 | float eInputGained = eInput * inputGain; 32 | 33 | //Integrating the error 34 | eIntegral += eInputGained * dT.count(); 35 | //Derivative of error 36 | float eDeriv = (eInputGained - ePrevious) / dT.count(); 37 | //Store the current error as previous 38 | ePrevious = eInputGained; 39 | //Calculate the control signal 40 | controlOutput = Kp * eInputGained + Ki * eIntegral + Kd * eDeriv; 41 | 42 | return controlOutput; 43 | } 44 | 45 | float PIDController::calculateOutput(float eInput, std::chrono::duration sampleTime){ 46 | //Store the new sample time 47 | dT = sampleTime; 48 | return calculateOutput(eInput); 49 | } 50 | 51 | float PIDController::getOutput() {return controlOutput;} 52 | -------------------------------------------------------------------------------- /Sensors/Coordinate.h: -------------------------------------------------------------------------------- 1 | #ifndef _Coordinate_H_ 2 | #define _Coordinate_H_ 3 | 4 | #include 5 | 6 | /** 7 | * @brief Class for coordinate. 8 | */ 9 | class Coordinate{ 10 | public: 11 | /** 12 | * @brief Constructor to assign this class with data 13 | * 14 | * @param[in] iLatitude The latitude 15 | * @param[in] iLongitude The longitude 16 | * @param[in] cNs North south indicator. It is either n or s 17 | * @param[in] cEw East west indicator. It is either e or w 18 | */ 19 | Coordinate(uint32_t iLatitude, uint32_t iLongitude, char cNs, char cEw); 20 | /** 21 | * @brief Empty constructor 22 | */ 23 | Coordinate(); 24 | /** 25 | * @brief Destroys the object. 26 | */ 27 | ~Coordinate(); 28 | /** 29 | * @brief Gets the longitude. 30 | * 31 | * @return The longitude. 32 | */ 33 | float getLongitude(); 34 | 35 | /** 36 | * @brief Gets the latitude. 37 | * 38 | * @return The latitude. 39 | */ 40 | float getLatitude(); 41 | 42 | /** 43 | * @brief Gets the east west indicator. 44 | * 45 | * @return The east west indicator. 46 | */ 47 | char getEW(); 48 | 49 | /** 50 | * @brief Gets the noth south indicator. 51 | * 52 | * @return The noth south indicator. 53 | */ 54 | char getNS(); 55 | 56 | /** 57 | * @brief print function 58 | */ 59 | void printLongLat(); 60 | 61 | private: 62 | //variables 63 | uint32_t latitude, longitude; 64 | char ns, ew; 65 | }; 66 | #endif 67 | -------------------------------------------------------------------------------- /Sensors/SensorConvertion.cpp: -------------------------------------------------------------------------------- 1 | #include "SensorConvertion.h" 2 | 3 | #define TRANSLATION 16383 4 | 5 | static SensorThreading sensorThreading; 6 | 7 | SensorConvertion::SensorConvertion(){ 8 | sensorThreading.startSensorGPSReading(); 9 | sensorThreading.startSensorIMUReading(); 10 | } 11 | SensorConvertion::~SensorConvertion(){ 12 | sensorThreading.stopSensorGPSReading(); 13 | sensorThreading.stopSensorIMUReading(); 14 | } 15 | 16 | DataWXYZ SensorConvertion::longLatToXYZ(){ 17 | if (sensorThreading.GPSindexR < sensorThreading.GPSindexW){ 18 | Coordinate coord = sensorThreading.GPSCoordinates[sensorThreading.GPSindexR % 10]; 19 | 20 | float cosLat = cos(coord.getLatitude() * M_PI / 180.0); 21 | float sinLat = sin(coord.getLatitude() * M_PI / 180.0); 22 | float cosLon = cos(coord.getLongitude() * M_PI / 180.0); 23 | float sinLon = sin(coord.getLongitude() * M_PI / 180.0); 24 | float C = 1.0 / sqrt(cosLat * cosLat + (1.0 - f) * (1.0 - f) * sinLat * sinLat); 25 | float S = (1.0 - f) * (1.0 - f) * C; 26 | float h = 0.0; 27 | 28 | DataWXYZ GPSposition = DataWXYZ( 29 | 0, 30 | (rad * C + h) * cosLat * cosLon / TRANSLATION, 31 | (rad * C + h) * cosLat * sinLon / TRANSLATION, 32 | (rad * S + h) * sinLat / TRANSLATION 33 | ); 34 | 35 | //printf("GPS: "); 36 | //GPSposition.printData(); 37 | 38 | sensorThreading.GPSindexR++; 39 | 40 | return GPSposition; 41 | } 42 | 43 | printf("GPS Reading waiting!\r\n"); 44 | return DataWXYZ(0, 0, 0, 0); 45 | } 46 | 47 | DataWXYZ SensorConvertion::convertIMUValues(DataWXYZ *location){ 48 | if (sensorThreading.IMUindexR < sensorThreading.IMUindexW){ 49 | DataWXYZ data = sensorThreading.IMUValues[sensorThreading.IMUindexR % 10]; 50 | 51 | 52 | float w = data.getW() * 360; 53 | float x = (data.getX() + location->getX()); 54 | float y = (data.getY() + location->getY()); 55 | float z = (data.getZ() + location->getZ()); 56 | 57 | lastCalculation = DataWXYZ(w,x,y,z); 58 | 59 | //printf("IMU: "); 60 | //lastCalculation.printData(); 61 | 62 | sensorThreading.IMUindexR++; 63 | 64 | return lastCalculation; 65 | } 66 | 67 | printf("IMU Reading waiting!\r\n"); 68 | return DataWXYZ(0, 0, 0, 0); 69 | } 70 | -------------------------------------------------------------------------------- /PIDController.h: -------------------------------------------------------------------------------- 1 | //This file contains the definition of the PIDController class 2 | #ifndef _PIDCONTROLLER_H_ 3 | #define _PIDCONTROLLER_H_ 4 | 5 | #include 6 | 7 | 8 | /** 9 | * @brief Class implemention a PID controller 10 | */ 11 | class PIDController{ 12 | public: 13 | /** 14 | * @brief Default constructor 15 | */ 16 | PIDController(); 17 | /** 18 | * @brief Constructor without sampleTime 19 | * 20 | * @param[in] p Gain of the P controller 21 | * @param[in] i Gain of the I controller 22 | * @param[in] d Gain of the D controller 23 | * @param[in] prev The previous value of the error signal 24 | * @param[in] integral The starting integrated value 25 | * @param[in] iGain The input gain 26 | */ 27 | PIDController(float p, float i, float d, float prev, float integral, float iGain); 28 | 29 | /** 30 | * @brief Constructor with sampleTime 31 | * 32 | * @param[in] p Gain of the P controller 33 | * @param[in] i Gain of the I controller 34 | * @param[in] d Gain of the D controller 35 | * @param[in] prev The previous value of the error signal 36 | * @param[in] integral The starting integrated value 37 | * @param[in] iGain The input gain 38 | * @param[in] sampleTime The sample time 39 | */ 40 | PIDController(float p, float i, float d, float prev, float integral, float iGain, std::chrono::duration sampleTime); 41 | 42 | /** 43 | * @brief Destroys the object. 44 | */ 45 | ~PIDController(); 46 | 47 | 48 | /** 49 | * @brief Calculates the output. 50 | * 51 | * @param[in] eInput The error input 52 | * 53 | * @return The output control signal. 54 | */ 55 | float calculateOutput(float eInput); 56 | 57 | /** 58 | * @brief Calculates the output. 59 | * 60 | * @param[in] eInput The error input 61 | * @param[in] sampleTime The sample time 62 | * 63 | * @return The output. 64 | */ 65 | float calculateOutput(float eInput, std::chrono::duration sampleTime); 66 | 67 | /** 68 | * @brief Gets the last control signal output. 69 | * 70 | * @return The output control signal. 71 | */ 72 | float getOutput(); 73 | 74 | float Kp, Ki, Kd, inputGain; //! dT; //! 14 | #include 15 | #include 16 | #include 17 | 18 | /** 19 | * @brief Class for sensor threading. 20 | * @details From here thread can be started to accuire data. 21 | */ 22 | class SensorThreading 23 | { 24 | public: 25 | /** 26 | * @brief Starts sensor gps reading. 27 | */ 28 | void startSensorGPSReading(); 29 | /** 30 | * @brief Stops sensor gps reading. 31 | */ 32 | void stopSensorGPSReading(); 33 | /** 34 | * @brief Determines if gps running. 35 | * 36 | * @return True if gps running, False otherwise. 37 | */ 38 | bool isGPSRunning() { return GPSRunning; }; 39 | 40 | /** 41 | * @brief Starts sensor imu reading. 42 | */ 43 | void startSensorIMUReading(); 44 | /** 45 | * @brief Stops sensor imu reading. 46 | */ 47 | void stopSensorIMUReading(); 48 | /** 49 | * @brief Determines if imu running. 50 | * 51 | * @return True if imu running, False otherwise. 52 | */ 53 | bool isIMURunning() { return IMURunning; }; 54 | /** 55 | * @brief Gets the imu from queue. 56 | */ 57 | void getIMUFromQueue(); 58 | 59 | /** 60 | * @brief Starts sensor acceleration reading. 61 | */ 62 | void startSensorAccelerationReading(); 63 | /** 64 | * @brief Stops sensor acceleration reading. 65 | */ 66 | void stopSensorAccelerationReading(); 67 | /** 68 | * @brief Determines if acceleration running. 69 | * 70 | * @return True if acceleration running, False otherwise. 71 | */ 72 | bool isAccelerationRunning() { return AccelerationRunning; }; 73 | /** 74 | * @brief Gets the acceleration from queue. 75 | */ 76 | void getAccelerationFromQueue(); 77 | 78 | /* ------ Circular buffers ------*/ 79 | Coordinate GPSCoordinates[10] {Coordinate(0, 0, 'A', 'A')}; 80 | int GPSindexR = 0; 81 | int GPSindexW = 0; 82 | 83 | DataWXYZ IMUValues[10] {DataWXYZ(0,0,0,0)}; 84 | int IMUindexR = 0; 85 | int IMUindexW = 0; 86 | 87 | std::queue AccelerationPositions; 88 | /** 89 | * @brief Constructor 90 | */ 91 | SensorThreading(); 92 | /** 93 | * @brief Destroys the object. 94 | */ 95 | ~SensorThreading(); 96 | 97 | private: 98 | std::chrono::duration periodTime; 99 | std::chrono::time_point lastTime, currentTime; 100 | 101 | // GPS 102 | std::thread SensorGPSReadingThread; 103 | void SensorGPSReadingFunction(); 104 | bool GPSRunning = false; 105 | 106 | 107 | // IMU 108 | std::thread SensorIMUReadingThread; 109 | void SensorIMUReadingFunction(); 110 | bool IMURunning = false; 111 | 112 | // IMU 113 | std::thread SensorAccelerationReadingThread; 114 | void SensorAccelerationReadingFunction(); 115 | bool AccelerationRunning = false; 116 | }; 117 | 118 | #endif 119 | -------------------------------------------------------------------------------- /BoatController.h: -------------------------------------------------------------------------------- 1 | #ifndef _BOATCONTROLLER_H_ 2 | #define _BOATCONTROLLER_H_ 3 | 4 | #include "PhysicalDefinitions.h" 5 | #include 6 | #include 7 | 8 | 9 | /** 10 | * @brief Class that implements the controller of the boat 11 | */ 12 | class BoatController{ 13 | public: 14 | 15 | /** 16 | * @brief Constructor 17 | * 18 | * @param b Pointer to the boat object to control 19 | */ 20 | BoatController(Boat *b); 21 | 22 | /** 23 | * @brief Destroys the object. 24 | */ 25 | ~BoatController(); 26 | 27 | 28 | /** 29 | * @brief Starts the boatController internal thread. 30 | */ 31 | void startControl(); 32 | 33 | /** 34 | * @brief Stops the boatController internal thread. 35 | */ 36 | void stopControl(); 37 | 38 | /** 39 | * @brief Determines if the boatController thread is running. 40 | * 41 | * @return True if running, False otherwise. 42 | */ 43 | bool isRunning() {return running;}; 44 | 45 | /** 46 | * @brief Does a single control step. 47 | */ 48 | void singleStep(); 49 | 50 | float xSignal = 0.0; //!< The current control signal of the x position 51 | float ySignal = 0.0; //!< The current control signal of the y position 52 | float hSignal = 0.0; //!< The current control signal of the heading 53 | 54 | private: 55 | Boat *boat; //!< The pointer to the boat that is controlled by this class 56 | std::thread controlThread; //!< The internal thread that will control the boat periodically 57 | std::chrono::duration periodTime; //!< The current periodTime of the thread 58 | std::chrono::time_point lastTime, currentTime; //!< Used to determine the periodTime 59 | 60 | bool running = false; //!< Stores if the control thread is running or not 61 | 62 | //Controllers 63 | PIDController xController; //!< The PIDController of the x position 64 | PIDController yController; //!< The PIDController of the y position 65 | PIDController hController; //!< The PIDController of the heading 66 | 67 | /** 68 | * @brief The function that runs in the boatController controlThread 69 | */ 70 | void controlFunction(); 71 | 72 | /** 73 | * @brief Converts the heading control signal to a vector that can be used to control a thruster 74 | * 75 | * @param[in] hSignal The heading signal 76 | * @param[in] left The angle if the thruster has to turn the boat to the left 77 | * @param[in] right The angle if the thruster has to turn the boat to the right 78 | * 79 | * @return The vector for the thruster determined by the heading 80 | */ 81 | Vector2 getHeadingVector(float hSignal, float left, float right); 82 | 83 | /** 84 | * @brief Used to write left, or right to the output if the input is above or below a threshold 85 | * 86 | * @param[in] error The error signal 87 | * @param[in] threshold The threshold 88 | * @param[in] left The left angle 89 | * @param[in] right The right angle 90 | * 91 | * @return The angle associated to the input 92 | */ 93 | float thresholding(float error, float threshold, float left, float right); 94 | }; 95 | #endif 96 | -------------------------------------------------------------------------------- /Sensors/SensorThreading.cpp: -------------------------------------------------------------------------------- 1 | #include "SensorThreading.h" 2 | 3 | #define _DISPLAY_COORDINATES_SENSORTHREADING 4 | #define _DISPLAY_IMU_VALUES_SENSORTHREADING 5 | 6 | SensorThreading::SensorThreading(){} 7 | SensorThreading::~SensorThreading(){} 8 | 9 | //GPS module 10 | void SensorThreading::startSensorGPSReading(){ 11 | if (!GPSRunning){ 12 | GPSRunning = true; 13 | lastTime = std::chrono::high_resolution_clock::now(); 14 | SensorGPSReadingThread = std::thread(&SensorThreading::SensorGPSReadingFunction, this); 15 | } 16 | } 17 | 18 | void SensorThreading::stopSensorGPSReading(){ 19 | if (GPSRunning){ 20 | GPSRunning = false; 21 | SensorGPSReadingThread.join(); 22 | } 23 | } 24 | 25 | void SensorThreading::SensorGPSReadingFunction(){ 26 | SensorGPS sensorGPS; 27 | sensorGPS.create(); 28 | if (sensorGPS.connect() == 1){ 29 | stopSensorGPSReading(); 30 | } 31 | 32 | while (GPSRunning){ 33 | if (GPSindexW < GPSindexR + 2 ){ 34 | sensorGPS.determineCoordinates(); 35 | 36 | GPSCoordinates[GPSindexW % 10] = sensorGPS.getCoordinate(); 37 | #ifdef _DISPLAY_COORDINATES_SENSORTHREADING 38 | GPSCoordinates[GPSindexW % 10].printLongLat(); 39 | #endif 40 | GPSindexW++; 41 | } 42 | } 43 | sensorGPS.destroy(); 44 | } 45 | 46 | //IMU Module 47 | void SensorThreading::startSensorIMUReading(){ 48 | if (!IMURunning){ 49 | IMURunning = true; 50 | lastTime = std::chrono::high_resolution_clock::now(); 51 | SensorIMUReadingThread = std::thread(&SensorThreading::SensorIMUReadingFunction, this); 52 | } 53 | } 54 | 55 | void SensorThreading::stopSensorIMUReading(){ 56 | if (IMURunning){ 57 | IMURunning = false; 58 | SensorIMUReadingThread.join(); 59 | } 60 | } 61 | 62 | void SensorThreading::SensorIMUReadingFunction(){ 63 | SensorIMU sensorIMU; 64 | sensorIMU.create(); 65 | if (sensorIMU.connect() == 1){ 66 | stopSensorIMUReading(); 67 | } 68 | 69 | while (IMURunning){ 70 | if (IMUindexW < IMUindexR + 2 ){ 71 | 72 | sensorIMU.determineQuaternion(); 73 | IMUValues[IMUindexW % 10] = sensorIMU.getQuaternion(); 74 | #ifdef _DISPLAY_IMU_VALUES_SENSORTHREADING 75 | IMUValues[IMUindexW % 10].printData(); 76 | #endif 77 | IMUindexW++; 78 | } 79 | } 80 | sensorIMU.destroy(); 81 | } 82 | 83 | /*//Acceleration Module 84 | void SensorThreading::startSensorAccelerationReading(){ 85 | if (!AccelerationRunning){ 86 | AccelerationRunning = true; 87 | lastTime = std::chrono::high_resolution_clock::now(); 88 | SensorAccelerationReadingThread = std::thread(&SensorThreading::SensorAccelerationReadingFunction, this); 89 | } 90 | } 91 | 92 | void SensorThreading::stopSensorAccelerationReading(){ 93 | if (AccelerationRunning){ 94 | AccelerationRunning = false; 95 | SensorAccelerationReadingThread.join(); 96 | } 97 | } 98 | 99 | void SensorThreading::SensorAccelerationReadingFunction(){ 100 | SensorAccelerometer sensorAccelerometer; 101 | sensorAccelerometer.create(); 102 | if (sensorAccelerometer.connect() == 1){ 103 | stopSensorAccelerationReading(); 104 | } 105 | 106 | while (AccelerationRunning){ 107 | if (AccelerationPositions.size() < 10){ 108 | sensorAccelerometer.determineAcceleration(); 109 | AccelerationPositions.push(sensorAccelerometer.getAcceleration()); 110 | } 111 | } 112 | sensorAccelerometer.destroy(); 113 | } 114 | 115 | void SensorThreading::getAccelerationFromQueue(){ 116 | if (!AccelerationPositions.empty()){ 117 | printf("Acceleration:"); 118 | AccelerationPositions.front().printData(); 119 | AccelerationPositions.pop(); 120 | } 121 | }*/ 122 | -------------------------------------------------------------------------------- /Simulate.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "Simulate.h" 3 | #include "Integrator.h" 4 | #include 5 | 6 | //#define DEBUG_SIMULATE_DYNPOS 7 | #ifdef DEBUG_SIMULATE_DYNPOS 8 | #include 9 | #endif //DEBUG_SIMULATE_DYNPOS 10 | 11 | 12 | SimulatedWorld::SimulatedWorld(Boat* iboat, float idT): 13 | boat(iboat), 14 | dT(idT){} 15 | 16 | void SimulatedWorld::calculateWorldTick(){ 17 | //A integrator will be used to translate acceleration to velocity. 18 | static Integrator velocityX(dT, boat->currentSpeed.x); 19 | static Integrator velocityY(dT, boat->currentSpeed.y); 20 | //A integrator will be used to translate velocity to position. 21 | static Integrator positionX(dT, boat->currentPosition.x); 22 | static Integrator positionY(dT, boat->currentPosition.y); 23 | //A integrator will be used to translate torque / angular mass to radians per second. 24 | static Integrator radiansPerSecond(dT, boat->currentBoatAngularSpeed); 25 | //A integrator will be used to translate radians per second to radians. 26 | static Integrator radians(dT, boat->currentHeading); 27 | //Defining to-be-calculated forces on boat 28 | float currentTorque = 0; 29 | Vector2 localForce = 0; 30 | //Calculate each force from every thruster. 31 | #ifdef DEBUG_SIMULATE_DYNPOS 32 | std::cout << "*\tDebug data for void SimulatedWorld::calculateWorldTick()" << std::endl; 33 | #endif 34 | for (int i = 0; i < 2; ++i){ 35 | //First calculate the force the is acting on the motor 36 | float angle = boat->azimuthThruster[i].normalRotation + boat->azimuthThruster[i].rotation; 37 | Vector2 localForceOnMotor( 38 | cos(angle), 39 | sin(angle)); 40 | localForceOnMotor *= boat->azimuthThruster[i].throttle * boat->azimuthThruster[i].maxForce; 41 | /** 42 | * Caclulate the torque due to the forces from the motors. 43 | * Torque van be calculated by the cross product of the location and the force vector. 44 | */ 45 | currentTorque += 46 | (boat->azimuthThruster[i].localLocation.x * localForceOnMotor.y) - 47 | (boat->azimuthThruster[i].localLocation.y * localForceOnMotor.x); 48 | /** 49 | * Calculate the Force acting the same line of the position vector. 50 | * This will give the accelerating force on the boat. 51 | * This can be done by using the dot procuct of the two vectors and 52 | * point it in the direction of its local rotation 53 | */ 54 | localForce += localForceOnMotor; 55 | #ifdef DEBUG_SIMULATE_DYNPOS 56 | std::cout << "Results for motor[" << i << ']' << std::endl; 57 | std::cout << "motor position = " << boat->azimuthThruster[i].localLocation << std::endl; 58 | std::cout << "localForceOnMotor = " << localForceOnMotor << std::endl; 59 | std::cout << "currentTorque now = " << currentTorque << std::endl; 60 | std::cout << "localForce now = " << localForce << '\n' << std::endl; 61 | #endif 62 | } 63 | //Add damping to the torque 64 | currentTorque -= boat->currentBoatAngularSpeed * boat->angularDamping; 65 | //Translate the localForce to global force. 66 | Vector2 globalForce = localForce.rotated(boat->currentHeading); 67 | //Add damping to the global force 68 | #ifdef DEBUG_SIMULATE_DYNPOS 69 | std::cout << "*************************************" << std::endl; 70 | std::cout << "localForce total = " << localForce << std::endl; 71 | std::cout << "currentHeading = " << boat->currentHeading << std::endl; 72 | std::cout << "globalForce = " << globalForce << std::endl; 73 | std::cout << "currentTorque total = " << currentTorque << std::endl; 74 | std::cout << "*************************************" << std::endl; 75 | #endif 76 | globalForce -= (boat->currentSpeed * boat->directionalDamping.rotated(boat->currentHeading)); 77 | //Integrate acceleration to velocity 78 | boat->currentSpeed.x = velocityX.update(globalForce.x / boat->mass); 79 | boat->currentSpeed.y = velocityY.update(globalForce.y / boat->mass); 80 | //Integrate vellocity to accleration 81 | boat->currentPosition.x = positionX.update(velocityX.getCurrentOutput()); 82 | boat->currentPosition.y = positionY.update(velocityY.getCurrentOutput()); 83 | //integrate angular acceleration to angular velocity 84 | boat->currentBoatAngularSpeed = radiansPerSecond.update(currentTorque / boat->angularMass); 85 | //integrate angular velocity to angle 86 | boat->currentHeading = radians.update(radiansPerSecond.getCurrentOutput()); 87 | } 88 | -------------------------------------------------------------------------------- /main.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "PhysicalDefinitions.h" 4 | #include "BoatController.h" 5 | #include "Simulate.h" 6 | #include "MotorController.h" 7 | #include 8 | 9 | using namespace std; 10 | 11 | #define _INTERACTIVE_TERMINAL_DYNPOS_ 12 | 13 | int i, j; 14 | 15 | int main(void){ 16 | Boat boat; 17 | SimulatedWorld simulation(&boat, 0.001); 18 | BoatController boatController(&boat); 19 | boat.currentPosition.x = 0.0; 20 | boat.currentPosition.y = 0.0; 21 | boat.currentHeading = 0.0; 22 | boat.setpointPosition.x = 30.0; 23 | boat.setpointPosition.y = 0.0; 24 | boat.setpointHeading = 1.0; 25 | boat.mass = 10; 26 | boat.angularMass = 5; 27 | boat.azimuthThruster[0].localLocation = Vector2(0, 1); 28 | boat.azimuthThruster[0].maxForce = 10; 29 | boat.azimuthThruster[0].rotation = 0; 30 | boat.azimuthThruster[0].normalRotation = M_PI_2; 31 | boat.azimuthThruster[0].throttle = 0; 32 | boat.azimuthThruster[1].localLocation = Vector2(0, -1); 33 | boat.azimuthThruster[1].maxForce = 10; 34 | boat.azimuthThruster[1].rotation = 0; 35 | boat.azimuthThruster[1].normalRotation = M_PI_2; 36 | boat.azimuthThruster[1].throttle = 0; 37 | 38 | //Array used to let the Arduino communicate with us. Not used right now 39 | uint8_t flowRegister[32]; 40 | //Construct a UsbSocket object to communicate with the arduino/motorController 41 | FlowSerial::UsbSocket arduino(flowRegister, sizeof(flowRegister) / sizeof(flowRegister[0])); 42 | //Connect to the serial device. Useally /dev/ttyACM0 for Arduino's 43 | arduino.connectToDevice("/dev/ttyACM0", 115200); 44 | //Sleep to let the Arduino start up(get out of it's boatloader state) 45 | #ifdef _INTERACTIVE_TERMINAL_DYNPOS_ 46 | cout << "Starting Arduino" << endl; 47 | #endif 48 | usleep(2000000); 49 | 50 | //A class to simplify the handling of the boat 51 | static MotorController motorController(arduino); 52 | #ifdef _INTERACTIVE_TERMINAL_DYNPOS_ 53 | cout << "Starting engines" << endl; 54 | #endif 55 | motorController.startMotors(); 56 | #ifdef _INTERACTIVE_TERMINAL_DYNPOS_ 57 | cout << "Ready. Press enter to start" << endl; 58 | cin.get(); 59 | #endif 60 | cout << "time,thruster0rotation,thrust0,thruster1rotation,thrust1,x,y,heading,errorX,errorY,errorH,xSignal,ySignal,hSignal" << endl; 61 | for (i = 0; i < 45000; ++i) 62 | { 63 | for (j = 0; j < 10; ++j) 64 | { 65 | simulation.calculateWorldTick(); 66 | } 67 | 68 | boatController.singleStep(); 69 | 70 | if(i % 50 == 0){ 71 | float errorX = boat.setpointPosition.x - boat.currentPosition.x; 72 | float errorY = boat.setpointPosition.y - boat.currentPosition.y; 73 | float errorH = boat.setpointHeading - boat.currentHeading; 74 | 75 | cout.width(12); 76 | cout << ((i * 10) + j) * 0.001 << ","; 77 | cout.width(12); 78 | cout << boat.azimuthThruster[0].rotation + boat.azimuthThruster[0].normalRotation << ","; 79 | cout.width(12); 80 | cout << boat.azimuthThruster[0].throttle << ","; 81 | cout.width(12); 82 | cout << boat.azimuthThruster[1].rotation + boat.azimuthThruster[1].normalRotation << ","; 83 | cout.width(12); 84 | cout << boat.azimuthThruster[1].throttle << ","; 85 | cout.width(12); 86 | cout << boat.currentPosition.x << ","; 87 | cout.width(12); 88 | cout << boat.currentPosition.y << ","; 89 | cout.width(12); 90 | cout << boat.currentHeading << ","; 91 | cout.width(12); 92 | cout << errorX << ","; 93 | cout.width(12); 94 | cout << errorY << ","; 95 | cout.width(12); 96 | cout << errorH << ","; 97 | cout.width(12); 98 | cout << boatController.xSignal << ","; 99 | cout.width(12); 100 | cout << boatController.ySignal << ","; 101 | cout.width(12); 102 | cout << boatController.hSignal 103 | << endl; 104 | } 105 | 106 | motorController.setMotorFront(uint8_t(boat.azimuthThruster[0].throttle * 180)); 107 | motorController.setRotationFront(uint8_t(boat.azimuthThruster[0].rotation * 180 / (2*M_PI))); 108 | motorController.syncRegisters(); 109 | usleep(10000); 110 | } 111 | return 0; 112 | } 113 | -------------------------------------------------------------------------------- /BoatController.cpp: -------------------------------------------------------------------------------- 1 | #include "BoatController.h" 2 | #include 3 | #include "ExtraFunctions.h" 4 | #include "Vector2/Vector2.hpp" 5 | 6 | #define PI 3.14159265 7 | 8 | /* 9 | float BoatController::calculateHeading(Vector2 currentPosition, Vector2 setpointPosition){ 10 | float x = boat->setpointPosition.x - boat->currentPosition.x; 11 | float y = boat->setpointPosition.y - boat->currentPosition.y; 12 | 13 | return atan2 (y,x); 14 | } 15 | */ 16 | 17 | BoatController::BoatController(Boat *b) : boat(b) 18 | { 19 | //Create the PIDController instances 20 | //NEED TO ADD A WAY TO SET THE CONSTANTS 21 | xController = PIDController(0.3, 0.0, 1.8, 0.0, 0.0, 1.0); 22 | yController = PIDController(0.3, 0.0, 1.8, 0.0, 0.0, 1.0); 23 | hController = PIDController(2.0, 0.0, 5.0, 0.0, 0.0, (1.0 / M_PI)); 24 | } 25 | 26 | BoatController::~BoatController() 27 | { 28 | //stopControl(); 29 | } 30 | 31 | void BoatController::startControl() 32 | { 33 | running = true; 34 | lastTime = std::chrono::high_resolution_clock::now(); 35 | controlThread = std::thread(&BoatController::controlFunction, this); 36 | } 37 | 38 | void BoatController::stopControl() 39 | { 40 | running = false; 41 | controlThread.join(); 42 | } 43 | 44 | void BoatController::controlFunction() 45 | { 46 | while (running) 47 | { 48 | currentTime = std::chrono::high_resolution_clock::now(); 49 | periodTime = currentTime - lastTime; 50 | lastTime = currentTime; 51 | 52 | //Calculate the current error in the position data 53 | float errorX = boat->setpointPosition.x - boat->currentPosition.x; 54 | float errorY = boat->setpointPosition.y - boat->currentPosition.y; 55 | float errorH = boat->setpointHeading - boat->currentHeading; 56 | 57 | xSignal = xController.calculateOutput(errorX, periodTime); 58 | ySignal = yController.calculateOutput(errorY, periodTime); 59 | hSignal = hController.calculateOutput(errorH, periodTime); 60 | 61 | Vector2 positionVector(xSignal, ySignal); 62 | positionVector.rotate(-M_PI_2); 63 | 64 | Vector2 heading1Vector = BoatController::getHeadingVector(hSignal, M_PI_2, M_PI + M_PI_2); 65 | Vector2 heading2Vector = BoatController::getHeadingVector(hSignal, M_PI + M_PI_2, M_PI_2); 66 | ; 67 | 68 | Vector2 thruster1Vector = positionVector + heading1Vector; 69 | Vector2 thruster2Vector = positionVector + heading2Vector; 70 | 71 | if (thruster1Vector.absolute() > 0.01) 72 | { 73 | boat->azimuthThruster[0].throttle = limit(thruster1Vector.absolute(), (float)-1.0, (float)1.0); 74 | boat->azimuthThruster[0].rotation = atan2(thruster1Vector.y, thruster1Vector.x); 75 | } 76 | else 77 | { 78 | boat->azimuthThruster[0].throttle = 0.0; 79 | boat->azimuthThruster[0].rotation = 0.0; 80 | } 81 | 82 | if (thruster2Vector.absolute() > 0.01) 83 | { 84 | boat->azimuthThruster[1].throttle = limit(thruster2Vector.absolute(), (float)-1.0, (float)1.0); 85 | boat->azimuthThruster[1].rotation = atan2(thruster2Vector.y, thruster2Vector.x); 86 | } 87 | else 88 | { 89 | boat->azimuthThruster[1].throttle = 0.0; 90 | boat->azimuthThruster[1].rotation = 0.0; 91 | } 92 | 93 | //Pause this thread 94 | std::this_thread::sleep_for(std::chrono::milliseconds(10)); 95 | } 96 | } 97 | 98 | void BoatController::singleStep() 99 | { 100 | periodTime = std::chrono::duration(std::chrono::milliseconds(10)); 101 | 102 | //Calculate the current error in the position data 103 | float errorX = boat->setpointPosition.x - boat->currentPosition.x; 104 | float errorY = boat->setpointPosition.y - boat->currentPosition.y; 105 | float errorH = boat->setpointHeading - boat->currentHeading; 106 | 107 | xSignal = xController.calculateOutput(errorX, periodTime); 108 | ySignal = yController.calculateOutput(errorY, periodTime); 109 | hSignal = hController.calculateOutput(errorH, periodTime); 110 | 111 | Vector2 positionVector(xSignal, ySignal); 112 | positionVector.rotate(-M_PI_2); 113 | 114 | Vector2 heading1Vector = BoatController::getHeadingVector(hSignal, M_PI_2, M_PI + M_PI_2); 115 | Vector2 heading2Vector = BoatController::getHeadingVector(hSignal, M_PI + M_PI_2, M_PI_2); 116 | ; 117 | 118 | Vector2 thruster1Vector = positionVector + heading1Vector; 119 | Vector2 thruster2Vector = positionVector + heading2Vector; 120 | 121 | boat->azimuthThruster[0].throttle = limit(thruster1Vector.absolute(), (float)-1.0, (float)1.0); 122 | boat->azimuthThruster[0].rotation = atan2(thruster1Vector.y, thruster1Vector.x); 123 | 124 | boat->azimuthThruster[1].throttle = limit(thruster2Vector.absolute(), (float)-1.0, (float)1.0); 125 | boat->azimuthThruster[1].rotation = atan2(thruster2Vector.y, thruster2Vector.x); 126 | } 127 | 128 | Vector2 BoatController::getHeadingVector(float hSignal, float left, float right) 129 | { 130 | Vector2 out = {0.0, 0.0}; 131 | 132 | float throttle = (fabs(hSignal) > 0.01) ? fabs(hSignal) : 0.0; 133 | float angle = BoatController::thresholding(hSignal, 0.01, left, right); 134 | 135 | out.x = throttle * cos(angle); 136 | out.y = throttle * sin(angle); 137 | 138 | return out; 139 | } 140 | 141 | float BoatController::thresholding(float error, float threshold, float left, float right) 142 | { 143 | if (error > threshold) 144 | { 145 | return left; 146 | } 147 | else if (error < -threshold) 148 | { 149 | return right; 150 | } 151 | else 152 | { 153 | return 0.0; 154 | } 155 | } 156 | -------------------------------------------------------------------------------- /Sensors/Backup: -------------------------------------------------------------------------------- 1 | //h 2 | #ifndef _SensorIMU_H_ 3 | #define _SensorIMU_H_ 4 | 5 | #include "../PhysicalDefinitions.h" 6 | #include "ip_connection.h" 7 | #include "brick_imu_v2.h" 8 | 9 | #define HOST "localhost" 10 | #define PORT 4223 11 | #define IMUUID "5VGPJ3" // Change XYZ to the UID of your Bricklet 12 | 13 | 14 | class SensorIMU 15 | { 16 | public: 17 | // Create IP connection and device object 18 | void create(); 19 | 20 | // Calls ipcon_disconnect internally and destroys IMU-object 21 | void destroy(); 22 | 23 | // Connect to brickd, ipcon 24 | float connect(); 25 | 26 | // !!Don't use device before ipcon is connected!! 27 | // Register all data callback to function cb_all_data 28 | // Set period for all data callback to 0.1s (100ms) 29 | // Note: The all data callback is only called every 0.1 seconds 30 | // if the all data has changed since the last call! 31 | void registerCallback(float time); 32 | 33 | // Get current Acceleration 34 | float getAcceleration(); 35 | 36 | // Get current Magnetic Fiel 37 | float getMagneticField(); 38 | 39 | // Get current Angular Velocity 40 | float getAngularVelocity(); 41 | 42 | // Get current Euler Angle 43 | float getEulerAngle(); 44 | 45 | // Get current Quaternion 46 | float getQuaternion(); 47 | 48 | // Get current Linear Acceleration 49 | float getLinearAcceleration(); 50 | 51 | // Get current Gravity Vector 52 | float getGravityVector(); 53 | // Get current Temperature 54 | float getTemperature(); 55 | 56 | // Get current Calibration Status 57 | float getCalibrationStatus(); 58 | 59 | // Clean print of all registerd data 60 | void printAllData(); 61 | 62 | private: 63 | IPConnection ipcon; 64 | IMUV2 imu; 65 | bool callbackRegistered; 66 | int setIndex = 0; 67 | int16_t accelerationValues[3]; 68 | int16_t magneticFieldValues[3]; 69 | int16_t angularVelocityValues[3]; 70 | int16_t eulerAngleValues[3]; 71 | int16_t quaternionValues[4]; 72 | int16_t linearAccelerationValues[3]; 73 | int16_t gravityVectorValues[3]; 74 | int8_t temperatureValue; 75 | uint8_t calibrationStatus; 76 | 77 | void cb_all_data(int16_t acceleration[3], int16_t magnetic_field[3], 78 | int16_t angular_velocity[3], int16_t euler_angle[3], 79 | int16_t quaternion[4], int16_t linear_acceleration[3], 80 | int16_t gravity_vector[3], int8_t temperature, 81 | uint8_t calibration_status, void *user_data); 82 | }; 83 | 84 | #endif 85 | 86 | //cpp 87 | #include "SensorIMU.h" 88 | 89 | void SensorIMU::create(){ 90 | ipcon_create(&ipcon); 91 | imu_v2_create(&imu, IMUUID, &ipcon); 92 | } 93 | 94 | void SensorIMU::destroy(){ 95 | imu_v2_destroy(&imu); 96 | ipcon_destroy(&ipcon); 97 | } 98 | 99 | float SensorIMU::connect(){ 100 | if(ipcon_connect(&ipcon, HOST, PORT) < 0) { 101 | fprintf(stderr, "Could not connect\n"); 102 | return 1; 103 | } 104 | return 0; 105 | } 106 | 107 | void SensorIMU::registerCallback(float time){ 108 | imu_v2_register_callback(&imu, 109 | IMU_V2_CALLBACK_ALL_DATA, 110 | (void *)cb_all_data, 111 | NULL); 112 | imu_v2_set_all_data_period(&imu, time); 113 | } 114 | 115 | float SensorIMU::getAcceleration(){return 1;} 116 | 117 | float SensorIMU::getMagneticField(){return 1;} 118 | 119 | float SensorIMU::getAngularVelocity(){return 1;} 120 | 121 | float SensorIMU::getEulerAngle(){return 1;} 122 | 123 | float SensorIMU::getQuaternion(){return 1;} 124 | 125 | float SensorIMU::getLinearAcceleration(){return 1;} 126 | 127 | float SensorIMU::getGravityVector(){return 1;} 128 | 129 | float SensorIMU::getTemperature(){return 1;} 130 | 131 | float SensorIMU::getCalibrationStatus(){return 1;} 132 | 133 | void SensorIMU::printAllData(){ 134 | printf("Acceleration x: %.02f y: %.02f z: %.02f m/s²\n" 135 | "Magnetic Field x: %.02f y: %.02f z: %.02f µT\n" 136 | "Angular Velocity x: %.02f y: %.02f z: %.02f °/s\n" 137 | "Euler Angle x: %.02f y: %.02f z: %.02f °\n" 138 | "Quaternion x: %.02f y: %.02f z: %.02f w: %.02f\n" 139 | "Linear Acceleration x: %.02f y: %.02f z: %.02f m/s²\n" 140 | "Gravity Vector x: %.02f y: %.02f z: %.02f m/s²\n" 141 | "Temperature %d °C\n" 142 | "Calibration Status %d\n\n", 143 | 144 | accelerationValues[0]/100.0, accelerationValues[1]/100.0, accelerationValues[2]/100.0, 145 | magneticFieldValues[0]/16.0, magneticFieldValues[1]/16.0, magneticFieldValues[2]/16.0, 146 | angularVelocityValues[0]/16.0, angularVelocityValues[1]/16.0, angularVelocityValues[2]/16.0, 147 | eulerAngleValues[0]/16.0, eulerAngleValues[1]/16.0, eulerAngleValues[2]/16.0, 148 | quaternionValues[1]/16383.0, quaternionValues[2]/16383.0, quaternionValues[3]/16383.0, quaternionValues[0]/16383.0, 149 | linearAccelerationValues[0]/100.0, linearAccelerationValues[1]/100.0, linearAccelerationValues[2]/100.0, 150 | gravityVectorValues[0]/100.0, gravityVectorValues[1]/100.0, gravityVectorValues[2]/100.0, 151 | temperatureValue, calibrationStatus); 152 | } 153 | 154 | void SensorIMU::cb_all_data(int16_t acceleration[3], int16_t magnetic_field[3], 155 | int16_t angular_velocity[3], int16_t euler_angle[3], 156 | int16_t quaternion[4], int16_t linear_acceleration[3], 157 | int16_t gravity_vector[3], int8_t temperature, 158 | uint8_t calibration_status, void *user_data){ 159 | (void)user_data; // avoid unused parameter warning 160 | 161 | for(int i = 0; i < 3; i++){ 162 | accelerationValues[i] = acceleration[i]; 163 | magneticFieldValues[i] = magnetic_field[i]; 164 | angularVelocityValues[i] = angular_velocity[i]; 165 | eulerAngleValues[i] = euler_angle[i]; 166 | quaternionValues[i] = quaternion[i]; 167 | linearAccelerationValues[i] = linear_acceleration[i]; 168 | gravityVectorValues[i] = gravity_vector[i]; 169 | } 170 | 171 | quaternionValues[3] = quaternion[3]; 172 | temperatureValue = temperature; 173 | calibrationStatus = calibration_status; 174 | } -------------------------------------------------------------------------------- /LICENCE: -------------------------------------------------------------------------------- 1 | GNU LESSER GENERAL PUBLIC LICENSE 2 | Version 3, 29 June 2007 3 | 4 | Copyright (C) 2007 Free Software Foundation, Inc. 5 | Everyone is permitted to copy and distribute verbatim copies 6 | of this license document, but changing it is not allowed. 7 | 8 | 9 | This version of the GNU Lesser General Public License incorporates 10 | the terms and conditions of version 3 of the GNU General Public 11 | License, supplemented by the additional permissions listed below. 12 | 13 | 0. Additional Definitions. 14 | 15 | As used herein, "this License" refers to version 3 of the GNU Lesser 16 | General Public License, and the "GNU GPL" refers to version 3 of the GNU 17 | General Public License. 18 | 19 | "The Library" refers to a covered work governed by this License, 20 | other than an Application or a Combined Work as defined below. 21 | 22 | An "Application" is any work that makes use of an interface provided 23 | by the Library, but which is not otherwise based on the Library. 24 | Defining a subclass of a class defined by the Library is deemed a mode 25 | of using an interface provided by the Library. 26 | 27 | A "Combined Work" is a work produced by combining or linking an 28 | Application with the Library. The particular version of the Library 29 | with which the Combined Work was made is also called the "Linked 30 | Version". 31 | 32 | The "Minimal Corresponding Source" for a Combined Work means the 33 | Corresponding Source for the Combined Work, excluding any source code 34 | for portions of the Combined Work that, considered in isolation, are 35 | based on the Application, and not on the Linked Version. 36 | 37 | The "Corresponding Application Code" for a Combined Work means the 38 | object code and/or source code for the Application, including any data 39 | and utility programs needed for reproducing the Combined Work from the 40 | Application, but excluding the System Libraries of the Combined Work. 41 | 42 | 1. Exception to Section 3 of the GNU GPL. 43 | 44 | You may convey a covered work under sections 3 and 4 of this License 45 | without being bound by section 3 of the GNU GPL. 46 | 47 | 2. Conveying Modified Versions. 48 | 49 | If you modify a copy of the Library, and, in your modifications, a 50 | facility refers to a function or data to be supplied by an Application 51 | that uses the facility (other than as an argument passed when the 52 | facility is invoked), then you may convey a copy of the modified 53 | version: 54 | 55 | a) under this License, provided that you make a good faith effort to 56 | ensure that, in the event an Application does not supply the 57 | function or data, the facility still operates, and performs 58 | whatever part of its purpose remains meaningful, or 59 | 60 | b) under the GNU GPL, with none of the additional permissions of 61 | this License applicable to that copy. 62 | 63 | 3. Object Code Incorporating Material from Library Header Files. 64 | 65 | The object code form of an Application may incorporate material from 66 | a header file that is part of the Library. You may convey such object 67 | code under terms of your choice, provided that, if the incorporated 68 | material is not limited to numerical parameters, data structure 69 | layouts and accessors, or small macros, inline functions and templates 70 | (ten or fewer lines in length), you do both of the following: 71 | 72 | a) Give prominent notice with each copy of the object code that the 73 | Library is used in it and that the Library and its use are 74 | covered by this License. 75 | 76 | b) Accompany the object code with a copy of the GNU GPL and this license 77 | document. 78 | 79 | 4. Combined Works. 80 | 81 | You may convey a Combined Work under terms of your choice that, 82 | taken together, effectively do not restrict modification of the 83 | portions of the Library contained in the Combined Work and reverse 84 | engineering for debugging such modifications, if you also do each of 85 | the following: 86 | 87 | a) Give prominent notice with each copy of the Combined Work that 88 | the Library is used in it and that the Library and its use are 89 | covered by this License. 90 | 91 | b) Accompany the Combined Work with a copy of the GNU GPL and this license 92 | document. 93 | 94 | c) For a Combined Work that displays copyright notices during 95 | execution, include the copyright notice for the Library among 96 | these notices, as well as a reference directing the user to the 97 | copies of the GNU GPL and this license document. 98 | 99 | d) Do one of the following: 100 | 101 | 0) Convey the Minimal Corresponding Source under the terms of this 102 | License, and the Corresponding Application Code in a form 103 | suitable for, and under terms that permit, the user to 104 | recombine or relink the Application with a modified version of 105 | the Linked Version to produce a modified Combined Work, in the 106 | manner specified by section 6 of the GNU GPL for conveying 107 | Corresponding Source. 108 | 109 | 1) Use a suitable shared library mechanism for linking with the 110 | Library. A suitable mechanism is one that (a) uses at run time 111 | a copy of the Library already present on the user's computer 112 | system, and (b) will operate properly with a modified version 113 | of the Library that is interface-compatible with the Linked 114 | Version. 115 | 116 | e) Provide Installation Information, but only if you would otherwise 117 | be required to provide such information under section 6 of the 118 | GNU GPL, and only to the extent that such information is 119 | necessary to install and execute a modified version of the 120 | Combined Work produced by recombining or relinking the 121 | Application with a modified version of the Linked Version. (If 122 | you use option 4d0, the Installation Information must accompany 123 | the Minimal Corresponding Source and Corresponding Application 124 | Code. If you use option 4d1, you must provide the Installation 125 | Information in the manner specified by section 6 of the GNU GPL 126 | for conveying Corresponding Source.) 127 | 128 | 5. Combined Libraries. 129 | 130 | You may place library facilities that are a work based on the 131 | Library side by side in a single library together with other library 132 | facilities that are not Applications and are not covered by this 133 | License, and convey such a combined library under terms of your 134 | choice, if you do both of the following: 135 | 136 | a) Accompany the combined library with a copy of the same work based 137 | on the Library, uncombined with any other library facilities, 138 | conveyed under the terms of this License. 139 | 140 | b) Give prominent notice with the combined library that part of it 141 | is a work based on the Library, and explaining where to find the 142 | accompanying uncombined form of the same work. 143 | 144 | 6. Revised Versions of the GNU Lesser General Public License. 145 | 146 | The Free Software Foundation may publish revised and/or new versions 147 | of the GNU Lesser General Public License from time to time. Such new 148 | versions will be similar in spirit to the present version, but may 149 | differ in detail to address new problems or concerns. 150 | 151 | Each version is given a distinguishing version number. If the 152 | Library as you received it specifies that a certain numbered version 153 | of the GNU Lesser General Public License "or any later version" 154 | applies to it, you have the option of following the terms and 155 | conditions either of that published version or of any later version 156 | published by the Free Software Foundation. If the Library as you 157 | received it does not specify a version number of the GNU Lesser 158 | General Public License, you may choose any version of the GNU Lesser 159 | General Public License ever published by the Free Software Foundation. 160 | 161 | If the Library as you received it specifies that a proxy can decide 162 | whether future versions of the GNU Lesser General Public License shall 163 | apply, that proxy's public statement of acceptance of any version is 164 | permanent authorization for you to choose that version for the 165 | Library. 166 | -------------------------------------------------------------------------------- /Sensors/bricklet_accelerometer.h: -------------------------------------------------------------------------------- 1 | /* *********************************************************** 2 | * This file was automatically generated on 2016-09-08. * 3 | * * 4 | * C/C++ Bindings Version 2.1.12 * 5 | * * 6 | * If you have a bugfix for this file and want to commit it, * 7 | * please fix the bug in the generator. You can find a link * 8 | * to the generators git repository on tinkerforge.com * 9 | *************************************************************/ 10 | 11 | #ifndef BRICKLET_ACCELEROMETER_H 12 | #define BRICKLET_ACCELEROMETER_H 13 | 14 | #include "ip_connection.h" 15 | 16 | #ifdef __cplusplus 17 | extern "C" { 18 | #endif 19 | 20 | /** 21 | * \defgroup BrickletAccelerometer Accelerometer Bricklet 22 | */ 23 | 24 | /** 25 | * \ingroup BrickletAccelerometer 26 | * 27 | * Measures acceleration in three axis 28 | */ 29 | typedef Device Accelerometer; 30 | 31 | /** 32 | * \ingroup BrickletAccelerometer 33 | */ 34 | #define ACCELEROMETER_FUNCTION_GET_ACCELERATION 1 35 | 36 | /** 37 | * \ingroup BrickletAccelerometer 38 | */ 39 | #define ACCELEROMETER_FUNCTION_SET_ACCELERATION_CALLBACK_PERIOD 2 40 | 41 | /** 42 | * \ingroup BrickletAccelerometer 43 | */ 44 | #define ACCELEROMETER_FUNCTION_GET_ACCELERATION_CALLBACK_PERIOD 3 45 | 46 | /** 47 | * \ingroup BrickletAccelerometer 48 | */ 49 | #define ACCELEROMETER_FUNCTION_SET_ACCELERATION_CALLBACK_THRESHOLD 4 50 | 51 | /** 52 | * \ingroup BrickletAccelerometer 53 | */ 54 | #define ACCELEROMETER_FUNCTION_GET_ACCELERATION_CALLBACK_THRESHOLD 5 55 | 56 | /** 57 | * \ingroup BrickletAccelerometer 58 | */ 59 | #define ACCELEROMETER_FUNCTION_SET_DEBOUNCE_PERIOD 6 60 | 61 | /** 62 | * \ingroup BrickletAccelerometer 63 | */ 64 | #define ACCELEROMETER_FUNCTION_GET_DEBOUNCE_PERIOD 7 65 | 66 | /** 67 | * \ingroup BrickletAccelerometer 68 | */ 69 | #define ACCELEROMETER_FUNCTION_GET_TEMPERATURE 8 70 | 71 | /** 72 | * \ingroup BrickletAccelerometer 73 | */ 74 | #define ACCELEROMETER_FUNCTION_SET_CONFIGURATION 9 75 | 76 | /** 77 | * \ingroup BrickletAccelerometer 78 | */ 79 | #define ACCELEROMETER_FUNCTION_GET_CONFIGURATION 10 80 | 81 | /** 82 | * \ingroup BrickletAccelerometer 83 | */ 84 | #define ACCELEROMETER_FUNCTION_LED_ON 11 85 | 86 | /** 87 | * \ingroup BrickletAccelerometer 88 | */ 89 | #define ACCELEROMETER_FUNCTION_LED_OFF 12 90 | 91 | /** 92 | * \ingroup BrickletAccelerometer 93 | */ 94 | #define ACCELEROMETER_FUNCTION_IS_LED_ON 13 95 | 96 | /** 97 | * \ingroup BrickletAccelerometer 98 | */ 99 | #define ACCELEROMETER_FUNCTION_GET_IDENTITY 255 100 | 101 | /** 102 | * \ingroup BrickletAccelerometer 103 | * 104 | * Signature: \code void callback(int16_t x, int16_t y, int16_t z, void *user_data) \endcode 105 | * 106 | * This callback is triggered periodically with the period that is set by 107 | * {@link accelerometer_set_acceleration_callback_period}. The parameters are the 108 | * X, Y and Z acceleration. 109 | * 110 | * {@link ACCELEROMETER_CALLBACK_ACCELERATION} is only triggered if the acceleration has changed since the 111 | * last triggering. 112 | */ 113 | #define ACCELEROMETER_CALLBACK_ACCELERATION 14 114 | 115 | /** 116 | * \ingroup BrickletAccelerometer 117 | * 118 | * Signature: \code void callback(int16_t x, int16_t y, int16_t z, void *user_data) \endcode 119 | * 120 | * This callback is triggered when the threshold as set by 121 | * {@link accelerometer_set_acceleration_callback_threshold} is reached. 122 | * The parameters are the X, Y and Z acceleration. 123 | * 124 | * If the threshold keeps being reached, the callback is triggered periodically 125 | * with the period as set by {@link accelerometer_set_debounce_period}. 126 | */ 127 | #define ACCELEROMETER_CALLBACK_ACCELERATION_REACHED 15 128 | 129 | 130 | /** 131 | * \ingroup BrickletAccelerometer 132 | */ 133 | #define ACCELEROMETER_THRESHOLD_OPTION_OFF 'x' 134 | 135 | /** 136 | * \ingroup BrickletAccelerometer 137 | */ 138 | #define ACCELEROMETER_THRESHOLD_OPTION_OUTSIDE 'o' 139 | 140 | /** 141 | * \ingroup BrickletAccelerometer 142 | */ 143 | #define ACCELEROMETER_THRESHOLD_OPTION_INSIDE 'i' 144 | 145 | /** 146 | * \ingroup BrickletAccelerometer 147 | */ 148 | #define ACCELEROMETER_THRESHOLD_OPTION_SMALLER '<' 149 | 150 | /** 151 | * \ingroup BrickletAccelerometer 152 | */ 153 | #define ACCELEROMETER_THRESHOLD_OPTION_GREATER '>' 154 | 155 | /** 156 | * \ingroup BrickletAccelerometer 157 | */ 158 | #define ACCELEROMETER_DATA_RATE_OFF 0 159 | 160 | /** 161 | * \ingroup BrickletAccelerometer 162 | */ 163 | #define ACCELEROMETER_DATA_RATE_3HZ 1 164 | 165 | /** 166 | * \ingroup BrickletAccelerometer 167 | */ 168 | #define ACCELEROMETER_DATA_RATE_6HZ 2 169 | 170 | /** 171 | * \ingroup BrickletAccelerometer 172 | */ 173 | #define ACCELEROMETER_DATA_RATE_12HZ 3 174 | 175 | /** 176 | * \ingroup BrickletAccelerometer 177 | */ 178 | #define ACCELEROMETER_DATA_RATE_25HZ 4 179 | 180 | /** 181 | * \ingroup BrickletAccelerometer 182 | */ 183 | #define ACCELEROMETER_DATA_RATE_50HZ 5 184 | 185 | /** 186 | * \ingroup BrickletAccelerometer 187 | */ 188 | #define ACCELEROMETER_DATA_RATE_100HZ 6 189 | 190 | /** 191 | * \ingroup BrickletAccelerometer 192 | */ 193 | #define ACCELEROMETER_DATA_RATE_400HZ 7 194 | 195 | /** 196 | * \ingroup BrickletAccelerometer 197 | */ 198 | #define ACCELEROMETER_DATA_RATE_800HZ 8 199 | 200 | /** 201 | * \ingroup BrickletAccelerometer 202 | */ 203 | #define ACCELEROMETER_DATA_RATE_1600HZ 9 204 | 205 | /** 206 | * \ingroup BrickletAccelerometer 207 | */ 208 | #define ACCELEROMETER_FULL_SCALE_2G 0 209 | 210 | /** 211 | * \ingroup BrickletAccelerometer 212 | */ 213 | #define ACCELEROMETER_FULL_SCALE_4G 1 214 | 215 | /** 216 | * \ingroup BrickletAccelerometer 217 | */ 218 | #define ACCELEROMETER_FULL_SCALE_6G 2 219 | 220 | /** 221 | * \ingroup BrickletAccelerometer 222 | */ 223 | #define ACCELEROMETER_FULL_SCALE_8G 3 224 | 225 | /** 226 | * \ingroup BrickletAccelerometer 227 | */ 228 | #define ACCELEROMETER_FULL_SCALE_16G 4 229 | 230 | /** 231 | * \ingroup BrickletAccelerometer 232 | */ 233 | #define ACCELEROMETER_FILTER_BANDWIDTH_800HZ 0 234 | 235 | /** 236 | * \ingroup BrickletAccelerometer 237 | */ 238 | #define ACCELEROMETER_FILTER_BANDWIDTH_400HZ 1 239 | 240 | /** 241 | * \ingroup BrickletAccelerometer 242 | */ 243 | #define ACCELEROMETER_FILTER_BANDWIDTH_200HZ 2 244 | 245 | /** 246 | * \ingroup BrickletAccelerometer 247 | */ 248 | #define ACCELEROMETER_FILTER_BANDWIDTH_50HZ 3 249 | 250 | /** 251 | * \ingroup BrickletAccelerometer 252 | * 253 | * This constant is used to identify a Accelerometer Bricklet. 254 | * 255 | * The {@link accelerometer_get_identity} function and the 256 | * {@link IPCON_CALLBACK_ENUMERATE} callback of the IP Connection have a 257 | * \c device_identifier parameter to specify the Brick's or Bricklet's type. 258 | */ 259 | #define ACCELEROMETER_DEVICE_IDENTIFIER 250 260 | 261 | /** 262 | * \ingroup BrickletAccelerometer 263 | * 264 | * This constant represents the display name of a Accelerometer Bricklet. 265 | */ 266 | #define ACCELEROMETER_DEVICE_DISPLAY_NAME "Accelerometer Bricklet" 267 | 268 | /** 269 | * \ingroup BrickletAccelerometer 270 | * 271 | * Creates the device object \c accelerometer with the unique device ID \c uid and adds 272 | * it to the IPConnection \c ipcon. 273 | */ 274 | void accelerometer_create(Accelerometer *accelerometer, const char *uid, IPConnection *ipcon); 275 | 276 | /** 277 | * \ingroup BrickletAccelerometer 278 | * 279 | * Removes the device object \c accelerometer from its IPConnection and destroys it. 280 | * The device object cannot be used anymore afterwards. 281 | */ 282 | void accelerometer_destroy(Accelerometer *accelerometer); 283 | 284 | /** 285 | * \ingroup BrickletAccelerometer 286 | * 287 | * Returns the response expected flag for the function specified by the 288 | * \c function_id parameter. It is *true* if the function is expected to 289 | * send a response, *false* otherwise. 290 | * 291 | * For getter functions this is enabled by default and cannot be disabled, 292 | * because those functions will always send a response. For callback 293 | * configuration functions it is enabled by default too, but can be disabled 294 | * via the accelerometer_set_response_expected function. For setter functions it is 295 | * disabled by default and can be enabled. 296 | * 297 | * Enabling the response expected flag for a setter function allows to 298 | * detect timeouts and other error conditions calls of this setter as well. 299 | * The device will then send a response for this purpose. If this flag is 300 | * disabled for a setter function then no response is send and errors are 301 | * silently ignored, because they cannot be detected. 302 | */ 303 | int accelerometer_get_response_expected(Accelerometer *accelerometer, uint8_t function_id, bool *ret_response_expected); 304 | 305 | /** 306 | * \ingroup BrickletAccelerometer 307 | * 308 | * Changes the response expected flag of the function specified by the 309 | * \c function_id parameter. This flag can only be changed for setter 310 | * (default value: *false*) and callback configuration functions 311 | * (default value: *true*). For getter functions it is always enabled and 312 | * callbacks it is always disabled. 313 | * 314 | * Enabling the response expected flag for a setter function allows to detect 315 | * timeouts and other error conditions calls of this setter as well. The device 316 | * will then send a response for this purpose. If this flag is disabled for a 317 | * setter function then no response is send and errors are silently ignored, 318 | * because they cannot be detected. 319 | */ 320 | int accelerometer_set_response_expected(Accelerometer *accelerometer, uint8_t function_id, bool response_expected); 321 | 322 | /** 323 | * \ingroup BrickletAccelerometer 324 | * 325 | * Changes the response expected flag for all setter and callback configuration 326 | * functions of this device at once. 327 | */ 328 | int accelerometer_set_response_expected_all(Accelerometer *accelerometer, bool response_expected); 329 | 330 | /** 331 | * \ingroup BrickletAccelerometer 332 | * 333 | * Registers a callback with ID \c id to the function \c callback. The 334 | * \c user_data will be given as a parameter of the callback. 335 | */ 336 | void accelerometer_register_callback(Accelerometer *accelerometer, uint8_t id, void *callback, void *user_data); 337 | 338 | /** 339 | * \ingroup BrickletAccelerometer 340 | * 341 | * Returns the API version (major, minor, release) of the bindings for this 342 | * device. 343 | */ 344 | int accelerometer_get_api_version(Accelerometer *accelerometer, uint8_t ret_api_version[3]); 345 | 346 | /** 347 | * \ingroup BrickletAccelerometer 348 | * 349 | * Returns the acceleration in x, y and z direction. The values 350 | * are given in g/1000 (1g = 9.80665m/s²), not to be confused with grams. 351 | * 352 | * If you want to get the acceleration periodically, it is recommended 353 | * to use the callback {@link ACCELEROMETER_CALLBACK_ACCELERATION} and set the period with 354 | * {@link accelerometer_set_acceleration_callback_period}. 355 | */ 356 | int accelerometer_get_acceleration(Accelerometer *accelerometer, int16_t *ret_x, int16_t *ret_y, int16_t *ret_z); 357 | 358 | /** 359 | * \ingroup BrickletAccelerometer 360 | * 361 | * Sets the period in ms with which the {@link ACCELEROMETER_CALLBACK_ACCELERATION} callback is triggered 362 | * periodically. A value of 0 turns the callback off. 363 | * 364 | * {@link ACCELEROMETER_CALLBACK_ACCELERATION} is only triggered if the acceleration has changed since the 365 | * last triggering. 366 | * 367 | * The default value is 0. 368 | */ 369 | int accelerometer_set_acceleration_callback_period(Accelerometer *accelerometer, uint32_t period); 370 | 371 | /** 372 | * \ingroup BrickletAccelerometer 373 | * 374 | * Returns the period as set by {@link accelerometer_set_acceleration_callback_period}. 375 | */ 376 | int accelerometer_get_acceleration_callback_period(Accelerometer *accelerometer, uint32_t *ret_period); 377 | 378 | /** 379 | * \ingroup BrickletAccelerometer 380 | * 381 | * Sets the thresholds for the {@link ACCELEROMETER_CALLBACK_ACCELERATION_REACHED} callback. 382 | * 383 | * The following options are possible: 384 | * 385 | * \verbatim 386 | * "Option", "Description" 387 | * 388 | * "'x'", "Callback is turned off" 389 | * "'o'", "Callback is triggered when the acceleration is *outside* the min and max values" 390 | * "'i'", "Callback is triggered when the acceleration is *inside* the min and max values" 391 | * "'<'", "Callback is triggered when the acceleration is smaller than the min value (max is ignored)" 392 | * "'>'", "Callback is triggered when the acceleration is greater than the min value (max is ignored)" 393 | * \endverbatim 394 | * 395 | * The default value is ('x', 0, 0, 0, 0, 0, 0). 396 | */ 397 | int accelerometer_set_acceleration_callback_threshold(Accelerometer *accelerometer, char option, int16_t min_x, int16_t max_x, int16_t min_y, int16_t max_y, int16_t min_z, int16_t max_z); 398 | 399 | /** 400 | * \ingroup BrickletAccelerometer 401 | * 402 | * Returns the threshold as set by {@link accelerometer_set_acceleration_callback_threshold}. 403 | */ 404 | int accelerometer_get_acceleration_callback_threshold(Accelerometer *accelerometer, char *ret_option, int16_t *ret_min_x, int16_t *ret_max_x, int16_t *ret_min_y, int16_t *ret_max_y, int16_t *ret_min_z, int16_t *ret_max_z); 405 | 406 | /** 407 | * \ingroup BrickletAccelerometer 408 | * 409 | * Sets the period in ms with which the threshold callback 410 | * 411 | * * {@link ACCELEROMETER_CALLBACK_ACCELERATION_REACHED} 412 | * 413 | * is triggered, if the threshold 414 | * 415 | * * {@link accelerometer_set_acceleration_callback_threshold} 416 | * 417 | * keeps being reached. 418 | * 419 | * The default value is 100. 420 | */ 421 | int accelerometer_set_debounce_period(Accelerometer *accelerometer, uint32_t debounce); 422 | 423 | /** 424 | * \ingroup BrickletAccelerometer 425 | * 426 | * Returns the debounce period as set by {@link accelerometer_set_debounce_period}. 427 | */ 428 | int accelerometer_get_debounce_period(Accelerometer *accelerometer, uint32_t *ret_debounce); 429 | 430 | /** 431 | * \ingroup BrickletAccelerometer 432 | * 433 | * Returns the temperature of the accelerometer in °C. 434 | */ 435 | int accelerometer_get_temperature(Accelerometer *accelerometer, int16_t *ret_temperature); 436 | 437 | /** 438 | * \ingroup BrickletAccelerometer 439 | * 440 | * Configures the data rate, full scale range and filter bandwidth. 441 | * Possible values are: 442 | * 443 | * * Data rate of 0Hz to 1600Hz. 444 | * * Full scale range of -2G to +2G up to -16G to +16G. 445 | * * Filter bandwidth between 50Hz and 800Hz. 446 | * 447 | * Decreasing data rate or full scale range will also decrease the noise on 448 | * the data. 449 | * 450 | * The default values are 100Hz data rate, -4G to +4G range and 200Hz 451 | * filter bandwidth. 452 | */ 453 | int accelerometer_set_configuration(Accelerometer *accelerometer, uint8_t data_rate, uint8_t full_scale, uint8_t filter_bandwidth); 454 | 455 | /** 456 | * \ingroup BrickletAccelerometer 457 | * 458 | * Returns the configuration as set by {@link accelerometer_set_configuration}. 459 | */ 460 | int accelerometer_get_configuration(Accelerometer *accelerometer, uint8_t *ret_data_rate, uint8_t *ret_full_scale, uint8_t *ret_filter_bandwidth); 461 | 462 | /** 463 | * \ingroup BrickletAccelerometer 464 | * 465 | * Enables the LED on the Bricklet. 466 | */ 467 | int accelerometer_led_on(Accelerometer *accelerometer); 468 | 469 | /** 470 | * \ingroup BrickletAccelerometer 471 | * 472 | * Disables the LED on the Bricklet. 473 | */ 474 | int accelerometer_led_off(Accelerometer *accelerometer); 475 | 476 | /** 477 | * \ingroup BrickletAccelerometer 478 | * 479 | * Returns *true* if the LED is enabled, *false* otherwise. 480 | */ 481 | int accelerometer_is_led_on(Accelerometer *accelerometer, bool *ret_on); 482 | 483 | /** 484 | * \ingroup BrickletAccelerometer 485 | * 486 | * Returns the UID, the UID where the Bricklet is connected to, 487 | * the position, the hardware and firmware version as well as the 488 | * device identifier. 489 | * 490 | * The position can be 'a', 'b', 'c' or 'd'. 491 | * 492 | * The device identifier numbers can be found :ref:`here `. 493 | * |device_identifier_constant| 494 | */ 495 | int accelerometer_get_identity(Accelerometer *accelerometer, char ret_uid[8], char ret_connected_uid[8], char *ret_position, uint8_t ret_hardware_version[3], uint8_t ret_firmware_version[3], uint16_t *ret_device_identifier); 496 | 497 | #ifdef __cplusplus 498 | } 499 | #endif 500 | 501 | #endif 502 | -------------------------------------------------------------------------------- /Sensors/bricklet_gps.h: -------------------------------------------------------------------------------- 1 | /* *********************************************************** 2 | * This file was automatically generated on 2016-09-08. * 3 | * * 4 | * C/C++ Bindings Version 2.1.12 * 5 | * * 6 | * If you have a bugfix for this file and want to commit it, * 7 | * please fix the bug in the generator. You can find a link * 8 | * to the generators git repository on tinkerforge.com * 9 | *************************************************************/ 10 | 11 | #ifndef BRICKLET_GPS_H 12 | #define BRICKLET_GPS_H 13 | 14 | #include "ip_connection.h" 15 | 16 | #ifdef __cplusplus 17 | extern "C" { 18 | #endif 19 | 20 | /** 21 | * \defgroup BrickletGPS GPS Bricklet 22 | */ 23 | 24 | /** 25 | * \ingroup BrickletGPS 26 | * 27 | * Determine position, velocity and altitude using GPS 28 | */ 29 | typedef Device GPS; 30 | 31 | /** 32 | * \ingroup BrickletGPS 33 | */ 34 | #define GPS_FUNCTION_GET_COORDINATES 1 35 | 36 | /** 37 | * \ingroup BrickletGPS 38 | */ 39 | #define GPS_FUNCTION_GET_STATUS 2 40 | 41 | /** 42 | * \ingroup BrickletGPS 43 | */ 44 | #define GPS_FUNCTION_GET_ALTITUDE 3 45 | 46 | /** 47 | * \ingroup BrickletGPS 48 | */ 49 | #define GPS_FUNCTION_GET_MOTION 4 50 | 51 | /** 52 | * \ingroup BrickletGPS 53 | */ 54 | #define GPS_FUNCTION_GET_DATE_TIME 5 55 | 56 | /** 57 | * \ingroup BrickletGPS 58 | */ 59 | #define GPS_FUNCTION_RESTART 6 60 | 61 | /** 62 | * \ingroup BrickletGPS 63 | */ 64 | #define GPS_FUNCTION_SET_COORDINATES_CALLBACK_PERIOD 7 65 | 66 | /** 67 | * \ingroup BrickletGPS 68 | */ 69 | #define GPS_FUNCTION_GET_COORDINATES_CALLBACK_PERIOD 8 70 | 71 | /** 72 | * \ingroup BrickletGPS 73 | */ 74 | #define GPS_FUNCTION_SET_STATUS_CALLBACK_PERIOD 9 75 | 76 | /** 77 | * \ingroup BrickletGPS 78 | */ 79 | #define GPS_FUNCTION_GET_STATUS_CALLBACK_PERIOD 10 80 | 81 | /** 82 | * \ingroup BrickletGPS 83 | */ 84 | #define GPS_FUNCTION_SET_ALTITUDE_CALLBACK_PERIOD 11 85 | 86 | /** 87 | * \ingroup BrickletGPS 88 | */ 89 | #define GPS_FUNCTION_GET_ALTITUDE_CALLBACK_PERIOD 12 90 | 91 | /** 92 | * \ingroup BrickletGPS 93 | */ 94 | #define GPS_FUNCTION_SET_MOTION_CALLBACK_PERIOD 13 95 | 96 | /** 97 | * \ingroup BrickletGPS 98 | */ 99 | #define GPS_FUNCTION_GET_MOTION_CALLBACK_PERIOD 14 100 | 101 | /** 102 | * \ingroup BrickletGPS 103 | */ 104 | #define GPS_FUNCTION_SET_DATE_TIME_CALLBACK_PERIOD 15 105 | 106 | /** 107 | * \ingroup BrickletGPS 108 | */ 109 | #define GPS_FUNCTION_GET_DATE_TIME_CALLBACK_PERIOD 16 110 | 111 | /** 112 | * \ingroup BrickletGPS 113 | */ 114 | #define GPS_FUNCTION_GET_IDENTITY 255 115 | 116 | /** 117 | * \ingroup BrickletGPS 118 | * 119 | * Signature: \code void callback(uint32_t latitude, char ns, uint32_t longitude, char ew, uint16_t pdop, uint16_t hdop, uint16_t vdop, uint16_t epe, void *user_data) \endcode 120 | * 121 | * This callback is triggered periodically with the period that is set by 122 | * {@link gps_set_coordinates_callback_period}. The parameters are the same 123 | * as for {@link gps_get_coordinates}. 124 | * 125 | * {@link GPS_CALLBACK_COORDINATES} is only triggered if the coordinates changed since the 126 | * last triggering and if there is currently a fix as indicated by 127 | * {@link gps_get_status}. 128 | */ 129 | #define GPS_CALLBACK_COORDINATES 17 130 | 131 | /** 132 | * \ingroup BrickletGPS 133 | * 134 | * Signature: \code void callback(uint8_t fix, uint8_t satellites_view, uint8_t satellites_used, void *user_data) \endcode 135 | * 136 | * This callback is triggered periodically with the period that is set by 137 | * {@link gps_set_status_callback_period}. The parameters are the same 138 | * as for {@link gps_get_status}. 139 | * 140 | * {@link GPS_CALLBACK_STATUS} is only triggered if the status changed since the 141 | * last triggering. 142 | */ 143 | #define GPS_CALLBACK_STATUS 18 144 | 145 | /** 146 | * \ingroup BrickletGPS 147 | * 148 | * Signature: \code void callback(int32_t altitude, int32_t geoidal_separation, void *user_data) \endcode 149 | * 150 | * This callback is triggered periodically with the period that is set by 151 | * {@link gps_set_altitude_callback_period}. The parameters are the same 152 | * as for {@link gps_get_altitude}. 153 | * 154 | * {@link GPS_CALLBACK_ALTITUDE} is only triggered if the altitude changed since the 155 | * last triggering and if there is currently a fix as indicated by 156 | * {@link gps_get_status}. 157 | */ 158 | #define GPS_CALLBACK_ALTITUDE 19 159 | 160 | /** 161 | * \ingroup BrickletGPS 162 | * 163 | * Signature: \code void callback(uint32_t course, uint32_t speed, void *user_data) \endcode 164 | * 165 | * This callback is triggered periodically with the period that is set by 166 | * {@link gps_set_motion_callback_period}. The parameters are the same 167 | * as for {@link gps_get_motion}. 168 | * 169 | * {@link GPS_CALLBACK_MOTION} is only triggered if the motion changed since the 170 | * last triggering and if there is currently a fix as indicated by 171 | * {@link gps_get_status}. 172 | */ 173 | #define GPS_CALLBACK_MOTION 20 174 | 175 | /** 176 | * \ingroup BrickletGPS 177 | * 178 | * Signature: \code void callback(uint32_t date, uint32_t time, void *user_data) \endcode 179 | * 180 | * This callback is triggered periodically with the period that is set by 181 | * {@link gps_set_date_time_callback_period}. The parameters are the same 182 | * as for {@link gps_get_date_time}. 183 | * 184 | * {@link GPS_CALLBACK_DATE_TIME} is only triggered if the date or time changed since the 185 | * last triggering. 186 | */ 187 | #define GPS_CALLBACK_DATE_TIME 21 188 | 189 | 190 | /** 191 | * \ingroup BrickletGPS 192 | */ 193 | #define GPS_FIX_NO_FIX 1 194 | 195 | /** 196 | * \ingroup BrickletGPS 197 | */ 198 | #define GPS_FIX_2D_FIX 2 199 | 200 | /** 201 | * \ingroup BrickletGPS 202 | */ 203 | #define GPS_FIX_3D_FIX 3 204 | 205 | /** 206 | * \ingroup BrickletGPS 207 | */ 208 | #define GPS_RESTART_TYPE_HOT_START 0 209 | 210 | /** 211 | * \ingroup BrickletGPS 212 | */ 213 | #define GPS_RESTART_TYPE_WARM_START 1 214 | 215 | /** 216 | * \ingroup BrickletGPS 217 | */ 218 | #define GPS_RESTART_TYPE_COLD_START 2 219 | 220 | /** 221 | * \ingroup BrickletGPS 222 | */ 223 | #define GPS_RESTART_TYPE_FACTORY_RESET 3 224 | 225 | /** 226 | * \ingroup BrickletGPS 227 | * 228 | * This constant is used to identify a GPS Bricklet. 229 | * 230 | * The {@link gps_get_identity} function and the 231 | * {@link IPCON_CALLBACK_ENUMERATE} callback of the IP Connection have a 232 | * \c device_identifier parameter to specify the Brick's or Bricklet's type. 233 | */ 234 | #define GPS_DEVICE_IDENTIFIER 222 235 | 236 | /** 237 | * \ingroup BrickletGPS 238 | * 239 | * This constant represents the display name of a GPS Bricklet. 240 | */ 241 | #define GPS_DEVICE_DISPLAY_NAME "GPS Bricklet" 242 | 243 | /** 244 | * \ingroup BrickletGPS 245 | * 246 | * Creates the device object \c gps with the unique device ID \c uid and adds 247 | * it to the IPConnection \c ipcon. 248 | */ 249 | void gps_create(GPS *gps, const char *uid, IPConnection *ipcon); 250 | 251 | /** 252 | * \ingroup BrickletGPS 253 | * 254 | * Removes the device object \c gps from its IPConnection and destroys it. 255 | * The device object cannot be used anymore afterwards. 256 | */ 257 | void gps_destroy(GPS *gps); 258 | 259 | /** 260 | * \ingroup BrickletGPS 261 | * 262 | * Returns the response expected flag for the function specified by the 263 | * \c function_id parameter. It is *true* if the function is expected to 264 | * send a response, *false* otherwise. 265 | * 266 | * For getter functions this is enabled by default and cannot be disabled, 267 | * because those functions will always send a response. For callback 268 | * configuration functions it is enabled by default too, but can be disabled 269 | * via the gps_set_response_expected function. For setter functions it is 270 | * disabled by default and can be enabled. 271 | * 272 | * Enabling the response expected flag for a setter function allows to 273 | * detect timeouts and other error conditions calls of this setter as well. 274 | * The device will then send a response for this purpose. If this flag is 275 | * disabled for a setter function then no response is send and errors are 276 | * silently ignored, because they cannot be detected. 277 | */ 278 | int gps_get_response_expected(GPS *gps, uint8_t function_id, bool *ret_response_expected); 279 | 280 | /** 281 | * \ingroup BrickletGPS 282 | * 283 | * Changes the response expected flag of the function specified by the 284 | * \c function_id parameter. This flag can only be changed for setter 285 | * (default value: *false*) and callback configuration functions 286 | * (default value: *true*). For getter functions it is always enabled and 287 | * callbacks it is always disabled. 288 | * 289 | * Enabling the response expected flag for a setter function allows to detect 290 | * timeouts and other error conditions calls of this setter as well. The device 291 | * will then send a response for this purpose. If this flag is disabled for a 292 | * setter function then no response is send and errors are silently ignored, 293 | * because they cannot be detected. 294 | */ 295 | int gps_set_response_expected(GPS *gps, uint8_t function_id, bool response_expected); 296 | 297 | /** 298 | * \ingroup BrickletGPS 299 | * 300 | * Changes the response expected flag for all setter and callback configuration 301 | * functions of this device at once. 302 | */ 303 | int gps_set_response_expected_all(GPS *gps, bool response_expected); 304 | 305 | /** 306 | * \ingroup BrickletGPS 307 | * 308 | * Registers a callback with ID \c id to the function \c callback. The 309 | * \c user_data will be given as a parameter of the callback. 310 | */ 311 | void gps_register_callback(GPS *gps, uint8_t id, void *callback, void *user_data); 312 | 313 | /** 314 | * \ingroup BrickletGPS 315 | * 316 | * Returns the API version (major, minor, release) of the bindings for this 317 | * device. 318 | */ 319 | int gps_get_api_version(GPS *gps, uint8_t ret_api_version[3]); 320 | 321 | /** 322 | * \ingroup BrickletGPS 323 | * 324 | * Returns the GPS coordinates. Latitude and longitude are given in the 325 | * ``DD.dddddd°`` format, the value 57123468 means 57.123468°. 326 | * The parameter ``ns`` and ``ew`` are the cardinal directions for 327 | * latitude and longitude. Possible values for ``ns`` and ``ew`` are 'N', 'S', 'E' 328 | * and 'W' (north, south, east and west). 329 | * 330 | * PDOP, HDOP and VDOP are the dilution of precision (DOP) values. They specify 331 | * the additional multiplicative effect of GPS satellite geometry on GPS 332 | * precision. See 333 | * `here `__ 334 | * for more information. The values are give in hundredths. 335 | * 336 | * EPE is the "Estimated Position Error". The EPE is given in cm. This is not the 337 | * absolute maximum error, it is the error with a specific confidence. See 338 | * `here `__ for more information. 339 | * 340 | * This data is only valid if there is currently a fix as indicated by 341 | * {@link gps_get_status}. 342 | */ 343 | int gps_get_coordinates(GPS *gps, uint32_t *ret_latitude, char *ret_ns, uint32_t *ret_longitude, char *ret_ew, uint16_t *ret_pdop, uint16_t *ret_hdop, uint16_t *ret_vdop, uint16_t *ret_epe); 344 | 345 | /** 346 | * \ingroup BrickletGPS 347 | * 348 | * Returns the current fix status, the number of satellites that are in view and 349 | * the number of satellites that are currently used. 350 | * 351 | * Possible fix status values can be: 352 | * 353 | * \verbatim 354 | * "Value", "Description" 355 | * 356 | * "1", "No Fix, {@link gps_get_coordinates}, {@link gps_get_altitude} and {@link gps_get_motion} return invalid data" 357 | * "2", "2D Fix, only {@link gps_get_coordinates} and {@link gps_get_motion} return valid data" 358 | * "3", "3D Fix, {@link gps_get_coordinates}, {@link gps_get_altitude} and {@link gps_get_motion} return valid data" 359 | * \endverbatim 360 | * 361 | * There is also a :ref:`blue LED ` on the Bricklet that 362 | * indicates the fix status. 363 | */ 364 | int gps_get_status(GPS *gps, uint8_t *ret_fix, uint8_t *ret_satellites_view, uint8_t *ret_satellites_used); 365 | 366 | /** 367 | * \ingroup BrickletGPS 368 | * 369 | * Returns the current altitude and corresponding geoidal separation. 370 | * 371 | * Both values are given in cm. 372 | * 373 | * This data is only valid if there is currently a fix as indicated by 374 | * {@link gps_get_status}. 375 | */ 376 | int gps_get_altitude(GPS *gps, int32_t *ret_altitude, int32_t *ret_geoidal_separation); 377 | 378 | /** 379 | * \ingroup BrickletGPS 380 | * 381 | * Returns the current course and speed. Course is given in hundredths degree 382 | * and speed is given in hundredths km/h. A course of 0° means the Bricklet is 383 | * traveling north bound and 90° means it is traveling east bound. 384 | * 385 | * Please note that this only returns useful values if an actual movement 386 | * is present. 387 | * 388 | * This data is only valid if there is currently a fix as indicated by 389 | * {@link gps_get_status}. 390 | */ 391 | int gps_get_motion(GPS *gps, uint32_t *ret_course, uint32_t *ret_speed); 392 | 393 | /** 394 | * \ingroup BrickletGPS 395 | * 396 | * Returns the current date and time. The date is 397 | * given in the format ``ddmmyy`` and the time is given 398 | * in the format ``hhmmss.sss``. For example, 140713 means 399 | * 14.05.13 as date and 195923568 means 19:59:23.568 as time. 400 | */ 401 | int gps_get_date_time(GPS *gps, uint32_t *ret_date, uint32_t *ret_time); 402 | 403 | /** 404 | * \ingroup BrickletGPS 405 | * 406 | * Restarts the GPS Bricklet, the following restart types are available: 407 | * 408 | * \verbatim 409 | * "Value", "Description" 410 | * 411 | * "0", "Hot start (use all available data in the NV store)" 412 | * "1", "Warm start (don't use ephemeris at restart)" 413 | * "2", "Cold start (don't use time, position, almanacs and ephemeris at restart)" 414 | * "3", "Factory reset (clear all system/user configurations at restart)" 415 | * \endverbatim 416 | */ 417 | int gps_restart(GPS *gps, uint8_t restart_type); 418 | 419 | /** 420 | * \ingroup BrickletGPS 421 | * 422 | * Sets the period in ms with which the {@link GPS_CALLBACK_COORDINATES} callback is triggered 423 | * periodically. A value of 0 turns the callback off. 424 | * 425 | * {@link GPS_CALLBACK_COORDINATES} is only triggered if the coordinates changed since the 426 | * last triggering. 427 | * 428 | * The default value is 0. 429 | */ 430 | int gps_set_coordinates_callback_period(GPS *gps, uint32_t period); 431 | 432 | /** 433 | * \ingroup BrickletGPS 434 | * 435 | * Returns the period as set by {@link gps_set_coordinates_callback_period}. 436 | */ 437 | int gps_get_coordinates_callback_period(GPS *gps, uint32_t *ret_period); 438 | 439 | /** 440 | * \ingroup BrickletGPS 441 | * 442 | * Sets the period in ms with which the {@link GPS_CALLBACK_STATUS} callback is triggered 443 | * periodically. A value of 0 turns the callback off. 444 | * 445 | * {@link GPS_CALLBACK_STATUS} is only triggered if the status changed since the 446 | * last triggering. 447 | * 448 | * The default value is 0. 449 | */ 450 | int gps_set_status_callback_period(GPS *gps, uint32_t period); 451 | 452 | /** 453 | * \ingroup BrickletGPS 454 | * 455 | * Returns the period as set by {@link gps_set_status_callback_period}. 456 | */ 457 | int gps_get_status_callback_period(GPS *gps, uint32_t *ret_period); 458 | 459 | /** 460 | * \ingroup BrickletGPS 461 | * 462 | * Sets the period in ms with which the {@link GPS_CALLBACK_ALTITUDE} callback is triggered 463 | * periodically. A value of 0 turns the callback off. 464 | * 465 | * {@link GPS_CALLBACK_ALTITUDE} is only triggered if the altitude changed since the 466 | * last triggering. 467 | * 468 | * The default value is 0. 469 | */ 470 | int gps_set_altitude_callback_period(GPS *gps, uint32_t period); 471 | 472 | /** 473 | * \ingroup BrickletGPS 474 | * 475 | * Returns the period as set by {@link gps_set_altitude_callback_period}. 476 | */ 477 | int gps_get_altitude_callback_period(GPS *gps, uint32_t *ret_period); 478 | 479 | /** 480 | * \ingroup BrickletGPS 481 | * 482 | * Sets the period in ms with which the {@link GPS_CALLBACK_MOTION} callback is triggered 483 | * periodically. A value of 0 turns the callback off. 484 | * 485 | * {@link GPS_CALLBACK_MOTION} is only triggered if the motion changed since the 486 | * last triggering. 487 | * 488 | * The default value is 0. 489 | */ 490 | int gps_set_motion_callback_period(GPS *gps, uint32_t period); 491 | 492 | /** 493 | * \ingroup BrickletGPS 494 | * 495 | * Returns the period as set by {@link gps_set_motion_callback_period}. 496 | */ 497 | int gps_get_motion_callback_period(GPS *gps, uint32_t *ret_period); 498 | 499 | /** 500 | * \ingroup BrickletGPS 501 | * 502 | * Sets the period in ms with which the {@link GPS_CALLBACK_DATE_TIME} callback is triggered 503 | * periodically. A value of 0 turns the callback off. 504 | * 505 | * {@link GPS_CALLBACK_DATE_TIME} is only triggered if the date or time changed since the 506 | * last triggering. 507 | * 508 | * The default value is 0. 509 | */ 510 | int gps_set_date_time_callback_period(GPS *gps, uint32_t period); 511 | 512 | /** 513 | * \ingroup BrickletGPS 514 | * 515 | * Returns the period as set by {@link gps_set_date_time_callback_period}. 516 | */ 517 | int gps_get_date_time_callback_period(GPS *gps, uint32_t *ret_period); 518 | 519 | /** 520 | * \ingroup BrickletGPS 521 | * 522 | * Returns the UID, the UID where the Bricklet is connected to, 523 | * the position, the hardware and firmware version as well as the 524 | * device identifier. 525 | * 526 | * The position can be 'a', 'b', 'c' or 'd'. 527 | * 528 | * The device identifier numbers can be found :ref:`here `. 529 | * |device_identifier_constant| 530 | */ 531 | int gps_get_identity(GPS *gps, char ret_uid[8], char ret_connected_uid[8], char *ret_position, uint8_t ret_hardware_version[3], uint8_t ret_firmware_version[3], uint16_t *ret_device_identifier); 532 | 533 | #ifdef __cplusplus 534 | } 535 | #endif 536 | 537 | #endif 538 | -------------------------------------------------------------------------------- /Sensors/ip_connection.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2012-2014 Matthias Bolte 3 | * Copyright (C) 2011 Olaf Lüke 4 | * 5 | * Redistribution and use in source and binary forms of this file, 6 | * with or without modification, are permitted. See the Creative 7 | * Commons Zero (CC0 1.0) License for more details. 8 | */ 9 | 10 | #ifndef IP_CONNECTION_H 11 | #define IP_CONNECTION_H 12 | 13 | /** 14 | * \defgroup IPConnection IP Connection 15 | */ 16 | 17 | #ifndef __STDC_LIMIT_MACROS 18 | #define __STDC_LIMIT_MACROS 19 | #endif 20 | #include 21 | #include 22 | #include 23 | 24 | #if !defined __cplusplus && defined __GNUC__ 25 | #include 26 | #endif 27 | 28 | #ifdef _WIN32 29 | #ifndef WIN32_LEAN_AND_MEAN 30 | #define WIN32_LEAN_AND_MEAN 31 | #endif 32 | #include 33 | #else 34 | #include 35 | #include 36 | #endif 37 | 38 | #ifdef __cplusplus 39 | extern "C" { 40 | #endif 41 | 42 | enum { 43 | E_OK = 0, 44 | E_TIMEOUT = -1, 45 | E_NO_STREAM_SOCKET = -2, 46 | E_HOSTNAME_INVALID = -3, 47 | E_NO_CONNECT = -4, 48 | E_NO_THREAD = -5, 49 | E_NOT_ADDED = -6, // unused since v2.0 50 | E_ALREADY_CONNECTED = -7, 51 | E_NOT_CONNECTED = -8, 52 | E_INVALID_PARAMETER = -9, // error response from device 53 | E_NOT_SUPPORTED = -10, // error response from device 54 | E_UNKNOWN_ERROR_CODE = -11 // error response from device 55 | }; 56 | 57 | #ifdef IPCON_EXPOSE_MILLISLEEP 58 | 59 | void millisleep(uint32_t msec); 60 | 61 | #endif // IPCON_EXPOSE_MILLISLEEP 62 | 63 | #ifdef IPCON_EXPOSE_INTERNALS 64 | 65 | typedef struct _Socket Socket; 66 | 67 | typedef struct { 68 | #ifdef _WIN32 69 | CRITICAL_SECTION handle; 70 | #else 71 | pthread_mutex_t handle; 72 | #endif 73 | } Mutex; 74 | 75 | void mutex_create(Mutex *mutex); 76 | 77 | void mutex_destroy(Mutex *mutex); 78 | 79 | void mutex_lock(Mutex *mutex); 80 | 81 | void mutex_unlock(Mutex *mutex); 82 | 83 | typedef struct { 84 | #ifdef _WIN32 85 | HANDLE handle; 86 | #else 87 | pthread_cond_t condition; 88 | pthread_mutex_t mutex; 89 | bool flag; 90 | #endif 91 | } Event; 92 | 93 | typedef struct { 94 | #ifdef _WIN32 95 | HANDLE handle; 96 | #else 97 | sem_t object; 98 | sem_t *pointer; 99 | #endif 100 | } Semaphore; 101 | 102 | typedef void (*ThreadFunction)(void *opaque); 103 | 104 | typedef struct { 105 | #ifdef _WIN32 106 | HANDLE handle; 107 | DWORD id; 108 | #else 109 | pthread_t handle; 110 | #endif 111 | ThreadFunction function; 112 | void *opaque; 113 | } Thread; 114 | 115 | typedef struct { 116 | Mutex mutex; 117 | int used; 118 | int allocated; 119 | uint32_t *keys; 120 | void **values; 121 | } Table; 122 | 123 | typedef struct _QueueItem { 124 | struct _QueueItem *next; 125 | int kind; 126 | void *data; 127 | } QueueItem; 128 | 129 | typedef struct { 130 | Mutex mutex; 131 | Semaphore semaphore; 132 | QueueItem *head; 133 | QueueItem *tail; 134 | } Queue; 135 | 136 | #if defined _MSC_VER || defined __BORLANDC__ 137 | #pragma pack(push) 138 | #pragma pack(1) 139 | #define ATTRIBUTE_PACKED 140 | #elif defined __GNUC__ 141 | #ifdef _WIN32 142 | // workaround struct packing bug in GCC 4.7 on Windows 143 | // http://gcc.gnu.org/bugzilla/show_bug.cgi?id=52991 144 | #define ATTRIBUTE_PACKED __attribute__((gcc_struct, packed)) 145 | #else 146 | #define ATTRIBUTE_PACKED __attribute__((packed)) 147 | #endif 148 | #else 149 | #error unknown compiler, do not know how to enable struct packing 150 | #endif 151 | 152 | typedef struct { 153 | uint32_t uid; // always little endian 154 | uint8_t length; 155 | uint8_t function_id; 156 | uint8_t sequence_number_and_options; 157 | uint8_t error_code_and_future_use; 158 | } ATTRIBUTE_PACKED PacketHeader; 159 | 160 | typedef struct { 161 | PacketHeader header; 162 | uint8_t payload[64]; 163 | uint8_t optional_data[8]; 164 | } ATTRIBUTE_PACKED Packet; 165 | 166 | #if defined _MSC_VER || defined __BORLANDC__ 167 | #pragma pack(pop) 168 | #endif 169 | #undef ATTRIBUTE_PACKED 170 | 171 | #endif // IPCON_EXPOSE_INTERNALS 172 | 173 | typedef struct _IPConnection IPConnection; 174 | typedef struct _IPConnectionPrivate IPConnectionPrivate; 175 | typedef struct _Device Device; 176 | typedef struct _DevicePrivate DevicePrivate; 177 | 178 | #ifdef IPCON_EXPOSE_INTERNALS 179 | 180 | typedef struct _CallbackContext CallbackContext; 181 | 182 | #endif 183 | 184 | typedef void (*EnumerateCallbackFunction)(const char *uid, 185 | const char *connected_uid, 186 | char position, 187 | uint8_t hardware_version[3], 188 | uint8_t firmware_version[3], 189 | uint16_t device_identifier, 190 | uint8_t enumeration_type, 191 | void *user_data); 192 | typedef void (*ConnectedCallbackFunction)(uint8_t connect_reason, 193 | void *user_data); 194 | typedef void (*DisconnectedCallbackFunction)(uint8_t disconnect_reason, 195 | void *user_data); 196 | 197 | #ifdef IPCON_EXPOSE_INTERNALS 198 | 199 | typedef void (*CallbackWrapperFunction)(DevicePrivate *device_p, Packet *packet); 200 | 201 | #endif 202 | 203 | /** 204 | * \internal 205 | */ 206 | struct _Device { 207 | DevicePrivate *p; 208 | }; 209 | 210 | #ifdef IPCON_EXPOSE_INTERNALS 211 | 212 | #define DEVICE_NUM_FUNCTION_IDS 256 213 | 214 | /** 215 | * \internal 216 | */ 217 | struct _DevicePrivate { 218 | int ref_count; 219 | 220 | uint32_t uid; // always host endian 221 | 222 | IPConnectionPrivate *ipcon_p; 223 | 224 | uint8_t api_version[3]; 225 | 226 | Mutex request_mutex; 227 | 228 | uint8_t expected_response_function_id; // protected by request_mutex 229 | uint8_t expected_response_sequence_number; // protected by request_mutex 230 | Mutex response_mutex; 231 | Packet response_packet; // protected by response_mutex 232 | Event response_event; 233 | int response_expected[DEVICE_NUM_FUNCTION_IDS]; 234 | 235 | void *registered_callbacks[DEVICE_NUM_FUNCTION_IDS]; 236 | void *registered_callback_user_data[DEVICE_NUM_FUNCTION_IDS]; 237 | CallbackWrapperFunction callback_wrappers[DEVICE_NUM_FUNCTION_IDS]; 238 | }; 239 | 240 | /** 241 | * \internal 242 | */ 243 | enum { 244 | DEVICE_RESPONSE_EXPECTED_INVALID_FUNCTION_ID = 0, 245 | DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE, // getter 246 | DEVICE_RESPONSE_EXPECTED_ALWAYS_FALSE, // callback 247 | DEVICE_RESPONSE_EXPECTED_TRUE, // setter 248 | DEVICE_RESPONSE_EXPECTED_FALSE // setter, default 249 | }; 250 | 251 | /** 252 | * \internal 253 | */ 254 | void device_create(Device *device, const char *uid, 255 | IPConnectionPrivate *ipcon_p, uint8_t api_version_major, 256 | uint8_t api_version_minor, uint8_t api_version_release); 257 | 258 | /** 259 | * \internal 260 | */ 261 | void device_release(DevicePrivate *device_p); 262 | 263 | /** 264 | * \internal 265 | */ 266 | int device_get_response_expected(DevicePrivate *device_p, uint8_t function_id, 267 | bool *ret_response_expected); 268 | 269 | /** 270 | * \internal 271 | */ 272 | int device_set_response_expected(DevicePrivate *device_p, uint8_t function_id, 273 | bool response_expected); 274 | 275 | /** 276 | * \internal 277 | */ 278 | int device_set_response_expected_all(DevicePrivate *device_p, bool response_expected); 279 | 280 | /** 281 | * \internal 282 | */ 283 | void device_register_callback(DevicePrivate *device_p, uint8_t id, void *callback, 284 | void *user_data); 285 | 286 | /** 287 | * \internal 288 | */ 289 | int device_get_api_version(DevicePrivate *device_p, uint8_t ret_api_version[3]); 290 | 291 | /** 292 | * \internal 293 | */ 294 | int device_send_request(DevicePrivate *device_p, Packet *request, Packet *response); 295 | 296 | #endif // IPCON_EXPOSE_INTERNALS 297 | 298 | /** 299 | * \ingroup IPConnection 300 | * 301 | * Possible IDs for ipcon_register_callback. 302 | */ 303 | enum { 304 | IPCON_CALLBACK_ENUMERATE = 253, 305 | IPCON_CALLBACK_CONNECTED = 0, 306 | IPCON_CALLBACK_DISCONNECTED = 1 307 | }; 308 | 309 | /** 310 | * \ingroup IPConnection 311 | * 312 | * Possible values for enumeration_type parameter of EnumerateCallback. 313 | */ 314 | enum { 315 | IPCON_ENUMERATION_TYPE_AVAILABLE = 0, 316 | IPCON_ENUMERATION_TYPE_CONNECTED = 1, 317 | IPCON_ENUMERATION_TYPE_DISCONNECTED = 2 318 | }; 319 | 320 | /** 321 | * \ingroup IPConnection 322 | * 323 | * Possible values for connect_reason parameter of ConnectedCallback. 324 | */ 325 | enum { 326 | IPCON_CONNECT_REASON_REQUEST = 0, 327 | IPCON_CONNECT_REASON_AUTO_RECONNECT = 1 328 | }; 329 | 330 | /** 331 | * \ingroup IPConnection 332 | * 333 | * Possible values for disconnect_reason parameter of DisconnectedCallback. 334 | */ 335 | enum { 336 | IPCON_DISCONNECT_REASON_REQUEST = 0, 337 | IPCON_DISCONNECT_REASON_ERROR = 1, 338 | IPCON_DISCONNECT_REASON_SHUTDOWN = 2 339 | }; 340 | 341 | /** 342 | * \ingroup IPConnection 343 | * 344 | * Possible return values of ipcon_get_connection_state. 345 | */ 346 | enum { 347 | IPCON_CONNECTION_STATE_DISCONNECTED = 0, 348 | IPCON_CONNECTION_STATE_CONNECTED = 1, 349 | IPCON_CONNECTION_STATE_PENDING = 2 // auto-reconnect in progress 350 | }; 351 | 352 | /** 353 | * \internal 354 | */ 355 | struct _IPConnection { 356 | IPConnectionPrivate *p; 357 | }; 358 | 359 | #ifdef IPCON_EXPOSE_INTERNALS 360 | 361 | #define IPCON_NUM_CALLBACK_IDS 256 362 | #define IPCON_MAX_SECRET_LENGTH 64 363 | 364 | /** 365 | * \internal 366 | */ 367 | typedef Device BrickDaemon; 368 | 369 | /** 370 | * \internal 371 | */ 372 | struct _IPConnectionPrivate { 373 | #ifdef _WIN32 374 | bool wsa_startup_done; // protected by socket_mutex 375 | #endif 376 | 377 | char *host; 378 | uint16_t port; 379 | 380 | uint32_t timeout; // in msec 381 | 382 | bool auto_reconnect; 383 | bool auto_reconnect_allowed; 384 | bool auto_reconnect_pending; 385 | 386 | Mutex sequence_number_mutex; 387 | uint8_t next_sequence_number; // protected by sequence_number_mutex 388 | 389 | Mutex authentication_mutex; // protects authentication handshake 390 | uint32_t next_authentication_nonce; // protected by authentication_mutex 391 | 392 | Mutex devices_ref_mutex; // protects DevicePrivate.ref_count 393 | Table devices; 394 | 395 | void *registered_callbacks[IPCON_NUM_CALLBACK_IDS]; 396 | void *registered_callback_user_data[IPCON_NUM_CALLBACK_IDS]; 397 | 398 | Mutex socket_mutex; 399 | Socket *socket; // protected by socket_mutex 400 | uint64_t socket_id; // protected by socket_mutex 401 | 402 | bool receive_flag; 403 | Thread receive_thread; // protected by socket_mutex 404 | 405 | CallbackContext *callback; 406 | 407 | bool disconnect_probe_flag; 408 | Thread disconnect_probe_thread; // protected by socket_mutex 409 | Event disconnect_probe_event; 410 | 411 | Semaphore wait; 412 | 413 | BrickDaemon brickd; 414 | }; 415 | 416 | #endif // IPCON_EXPOSE_INTERNALS 417 | 418 | /** 419 | * \ingroup IPConnection 420 | * 421 | * Creates an IP Connection object that can be used to enumerate the available 422 | * devices. It is also required for the constructor of Bricks and Bricklets. 423 | */ 424 | void ipcon_create(IPConnection *ipcon); 425 | 426 | /** 427 | * \ingroup IPConnection 428 | * 429 | * Destroys the IP Connection object. Calls ipcon_disconnect internally. 430 | * The connection to the Brick Daemon gets closed and the threads of the 431 | * IP Connection are terminated. 432 | */ 433 | void ipcon_destroy(IPConnection *ipcon); 434 | 435 | /** 436 | * \ingroup IPConnection 437 | * 438 | * Creates a TCP/IP connection to the given \c host and c\ port. The host and 439 | * port can point to a Brick Daemon or to a WIFI/Ethernet Extension. 440 | * 441 | * Devices can only be controlled when the connection was established 442 | * successfully. 443 | * 444 | * Blocks until the connection is established and returns an error code if 445 | * there is no Brick Daemon or WIFI/Ethernet Extension listening at the given 446 | * host and port. 447 | */ 448 | int ipcon_connect(IPConnection *ipcon, const char *host, uint16_t port); 449 | 450 | /** 451 | * \ingroup IPConnection 452 | * 453 | * Disconnects the TCP/IP connection from the Brick Daemon or the WIFI/Ethernet 454 | * Extension. 455 | */ 456 | int ipcon_disconnect(IPConnection *ipcon); 457 | 458 | /** 459 | * \ingroup IPConnection 460 | * 461 | * Performs an authentication handshake with the connected Brick Daemon or 462 | * WIFI/Ethernet Extension. If the handshake succeeds the connection switches 463 | * from non-authenticated to authenticated state and communication can 464 | * continue as normal. If the handshake fails then the connection gets closed. 465 | * Authentication can fail if the wrong secret was used or if authentication 466 | * is not enabled at all on the Brick Daemon or the WIFI/Ethernet Extension. 467 | * 468 | * For more information about authentication see 469 | * http://www.tinkerforge.com/en/doc/Tutorials/Tutorial_Authentication/Tutorial.html 470 | */ 471 | int ipcon_authenticate(IPConnection *ipcon, const char secret[64]); 472 | 473 | /** 474 | * \ingroup IPConnection 475 | * 476 | * Can return the following states: 477 | * 478 | * - IPCON_CONNECTION_STATE_DISCONNECTED: No connection is established. 479 | * - IPCON_CONNECTION_STATE_CONNECTED: A connection to the Brick Daemon or 480 | * the WIFI/Ethernet Extension is established. 481 | * - IPCON_CONNECTION_STATE_PENDING: IP Connection is currently trying to 482 | * connect. 483 | */ 484 | int ipcon_get_connection_state(IPConnection *ipcon); 485 | 486 | /** 487 | * \ingroup IPConnection 488 | * 489 | * Enables or disables auto-reconnect. If auto-reconnect is enabled, 490 | * the IP Connection will try to reconnect to the previously given 491 | * host and port, if the connection is lost. 492 | * 493 | * Default value is *true*. 494 | */ 495 | void ipcon_set_auto_reconnect(IPConnection *ipcon, bool auto_reconnect); 496 | 497 | /** 498 | * \ingroup IPConnection 499 | * 500 | * Returns *true* if auto-reconnect is enabled, *false* otherwise. 501 | */ 502 | bool ipcon_get_auto_reconnect(IPConnection *ipcon); 503 | 504 | /** 505 | * \ingroup IPConnection 506 | * 507 | * Sets the timeout in milliseconds for getters and for setters for which the 508 | * response expected flag is activated. 509 | * 510 | * Default timeout is 2500. 511 | */ 512 | void ipcon_set_timeout(IPConnection *ipcon, uint32_t timeout); 513 | 514 | /** 515 | * \ingroup IPConnection 516 | * 517 | * Returns the timeout as set by ipcon_set_timeout. 518 | */ 519 | uint32_t ipcon_get_timeout(IPConnection *ipcon); 520 | 521 | /** 522 | * \ingroup IPConnection 523 | * 524 | * Broadcasts an enumerate request. All devices will respond with an enumerate 525 | * callback. 526 | */ 527 | int ipcon_enumerate(IPConnection *ipcon); 528 | 529 | /** 530 | * \ingroup IPConnection 531 | * 532 | * Stops the current thread until ipcon_unwait is called. 533 | * 534 | * This is useful if you rely solely on callbacks for events, if you want 535 | * to wait for a specific callback or if the IP Connection was created in 536 | * a thread. 537 | * 538 | * ipcon_wait and ipcon_unwait act in the same way as "acquire" and "release" 539 | * of a semaphore. 540 | */ 541 | void ipcon_wait(IPConnection *ipcon); 542 | 543 | /** 544 | * \ingroup IPConnection 545 | * 546 | * Unwaits the thread previously stopped by ipcon_wait. 547 | * 548 | * ipcon_wait and ipcon_unwait act in the same way as "acquire" and "release" 549 | * of a semaphore. 550 | */ 551 | void ipcon_unwait(IPConnection *ipcon); 552 | 553 | /** 554 | * \ingroup IPConnection 555 | * 556 | * Registers a callback for a given ID. 557 | */ 558 | void ipcon_register_callback(IPConnection *ipcon, uint8_t id, 559 | void *callback, void *user_data); 560 | 561 | #ifdef IPCON_EXPOSE_INTERNALS 562 | 563 | /** 564 | * \internal 565 | */ 566 | int packet_header_create(PacketHeader *header, uint8_t length, 567 | uint8_t function_id, IPConnectionPrivate *ipcon_p, 568 | DevicePrivate *device_p); 569 | 570 | /** 571 | * \internal 572 | */ 573 | uint8_t packet_header_get_sequence_number(PacketHeader *header); 574 | 575 | /** 576 | * \internal 577 | */ 578 | void packet_header_set_sequence_number(PacketHeader *header, 579 | uint8_t sequence_number); 580 | 581 | /** 582 | * \internal 583 | */ 584 | uint8_t packet_header_get_response_expected(PacketHeader *header); 585 | 586 | /** 587 | * \internal 588 | */ 589 | void packet_header_set_response_expected(PacketHeader *header, 590 | uint8_t response_expected); 591 | 592 | /** 593 | * \internal 594 | */ 595 | uint8_t packet_header_get_error_code(PacketHeader *header); 596 | 597 | /** 598 | * \internal 599 | */ 600 | int16_t leconvert_int16_to(int16_t native); 601 | 602 | /** 603 | * \internal 604 | */ 605 | uint16_t leconvert_uint16_to(uint16_t native); 606 | 607 | /** 608 | * \internal 609 | */ 610 | int32_t leconvert_int32_to(int32_t native); 611 | 612 | /** 613 | * \internal 614 | */ 615 | uint32_t leconvert_uint32_to(uint32_t native); 616 | 617 | /** 618 | * \internal 619 | */ 620 | int64_t leconvert_int64_to(int64_t native); 621 | 622 | /** 623 | * \internal 624 | */ 625 | uint64_t leconvert_uint64_to(uint64_t native); 626 | 627 | /** 628 | * \internal 629 | */ 630 | float leconvert_float_to(float native); 631 | 632 | /** 633 | * \internal 634 | */ 635 | int16_t leconvert_int16_from(int16_t little); 636 | 637 | /** 638 | * \internal 639 | */ 640 | uint16_t leconvert_uint16_from(uint16_t little); 641 | 642 | /** 643 | * \internal 644 | */ 645 | int32_t leconvert_int32_from(int32_t little); 646 | 647 | /** 648 | * \internal 649 | */ 650 | uint32_t leconvert_uint32_from(uint32_t little); 651 | 652 | /** 653 | * \internal 654 | */ 655 | int64_t leconvert_int64_from(int64_t little); 656 | 657 | /** 658 | * \internal 659 | */ 660 | uint64_t leconvert_uint64_from(uint64_t little); 661 | 662 | /** 663 | * \internal 664 | */ 665 | float leconvert_float_from(float little); 666 | 667 | #endif // IPCON_EXPOSE_INTERNALS 668 | 669 | #ifdef __cplusplus 670 | } 671 | #endif 672 | 673 | #endif 674 | -------------------------------------------------------------------------------- /Sensors/bricklet_accelerometer.cpp: -------------------------------------------------------------------------------- 1 | /* *********************************************************** 2 | * This file was automatically generated on 2016-09-08. * 3 | * * 4 | * C/C++ Bindings Version 2.1.12 * 5 | * * 6 | * If you have a bugfix for this file and want to commit it, * 7 | * please fix the bug in the generator. You can find a link * 8 | * to the generators git repository on tinkerforge.com * 9 | *************************************************************/ 10 | 11 | 12 | #define IPCON_EXPOSE_INTERNALS 13 | 14 | #include "bricklet_accelerometer.h" 15 | 16 | #include 17 | 18 | #ifdef __cplusplus 19 | extern "C" { 20 | #endif 21 | 22 | 23 | 24 | typedef void (*AccelerationCallbackFunction)(int16_t, int16_t, int16_t, void *); 25 | 26 | typedef void (*AccelerationReachedCallbackFunction)(int16_t, int16_t, int16_t, void *); 27 | 28 | #if defined _MSC_VER || defined __BORLANDC__ 29 | #pragma pack(push) 30 | #pragma pack(1) 31 | #define ATTRIBUTE_PACKED 32 | #elif defined __GNUC__ 33 | #ifdef _WIN32 34 | // workaround struct packing bug in GCC 4.7 on Windows 35 | // http://gcc.gnu.org/bugzilla/show_bug.cgi?id=52991 36 | #define ATTRIBUTE_PACKED __attribute__((gcc_struct, packed)) 37 | #else 38 | #define ATTRIBUTE_PACKED __attribute__((packed)) 39 | #endif 40 | #else 41 | #error unknown compiler, do not know how to enable struct packing 42 | #endif 43 | 44 | typedef struct { 45 | PacketHeader header; 46 | } ATTRIBUTE_PACKED GetAcceleration_; 47 | 48 | typedef struct { 49 | PacketHeader header; 50 | int16_t x; 51 | int16_t y; 52 | int16_t z; 53 | } ATTRIBUTE_PACKED GetAccelerationResponse_; 54 | 55 | typedef struct { 56 | PacketHeader header; 57 | uint32_t period; 58 | } ATTRIBUTE_PACKED SetAccelerationCallbackPeriod_; 59 | 60 | typedef struct { 61 | PacketHeader header; 62 | } ATTRIBUTE_PACKED GetAccelerationCallbackPeriod_; 63 | 64 | typedef struct { 65 | PacketHeader header; 66 | uint32_t period; 67 | } ATTRIBUTE_PACKED GetAccelerationCallbackPeriodResponse_; 68 | 69 | typedef struct { 70 | PacketHeader header; 71 | char option; 72 | int16_t min_x; 73 | int16_t max_x; 74 | int16_t min_y; 75 | int16_t max_y; 76 | int16_t min_z; 77 | int16_t max_z; 78 | } ATTRIBUTE_PACKED SetAccelerationCallbackThreshold_; 79 | 80 | typedef struct { 81 | PacketHeader header; 82 | } ATTRIBUTE_PACKED GetAccelerationCallbackThreshold_; 83 | 84 | typedef struct { 85 | PacketHeader header; 86 | char option; 87 | int16_t min_x; 88 | int16_t max_x; 89 | int16_t min_y; 90 | int16_t max_y; 91 | int16_t min_z; 92 | int16_t max_z; 93 | } ATTRIBUTE_PACKED GetAccelerationCallbackThresholdResponse_; 94 | 95 | typedef struct { 96 | PacketHeader header; 97 | uint32_t debounce; 98 | } ATTRIBUTE_PACKED SetDebouncePeriod_; 99 | 100 | typedef struct { 101 | PacketHeader header; 102 | } ATTRIBUTE_PACKED GetDebouncePeriod_; 103 | 104 | typedef struct { 105 | PacketHeader header; 106 | uint32_t debounce; 107 | } ATTRIBUTE_PACKED GetDebouncePeriodResponse_; 108 | 109 | typedef struct { 110 | PacketHeader header; 111 | } ATTRIBUTE_PACKED GetTemperature_; 112 | 113 | typedef struct { 114 | PacketHeader header; 115 | int16_t temperature; 116 | } ATTRIBUTE_PACKED GetTemperatureResponse_; 117 | 118 | typedef struct { 119 | PacketHeader header; 120 | uint8_t data_rate; 121 | uint8_t full_scale; 122 | uint8_t filter_bandwidth; 123 | } ATTRIBUTE_PACKED SetConfiguration_; 124 | 125 | typedef struct { 126 | PacketHeader header; 127 | } ATTRIBUTE_PACKED GetConfiguration_; 128 | 129 | typedef struct { 130 | PacketHeader header; 131 | uint8_t data_rate; 132 | uint8_t full_scale; 133 | uint8_t filter_bandwidth; 134 | } ATTRIBUTE_PACKED GetConfigurationResponse_; 135 | 136 | typedef struct { 137 | PacketHeader header; 138 | } ATTRIBUTE_PACKED LEDOn_; 139 | 140 | typedef struct { 141 | PacketHeader header; 142 | } ATTRIBUTE_PACKED LEDOff_; 143 | 144 | typedef struct { 145 | PacketHeader header; 146 | } ATTRIBUTE_PACKED IsLEDOn_; 147 | 148 | typedef struct { 149 | PacketHeader header; 150 | bool on; 151 | } ATTRIBUTE_PACKED IsLEDOnResponse_; 152 | 153 | typedef struct { 154 | PacketHeader header; 155 | int16_t x; 156 | int16_t y; 157 | int16_t z; 158 | } ATTRIBUTE_PACKED AccelerationCallback_; 159 | 160 | typedef struct { 161 | PacketHeader header; 162 | int16_t x; 163 | int16_t y; 164 | int16_t z; 165 | } ATTRIBUTE_PACKED AccelerationReachedCallback_; 166 | 167 | typedef struct { 168 | PacketHeader header; 169 | } ATTRIBUTE_PACKED GetIdentity_; 170 | 171 | typedef struct { 172 | PacketHeader header; 173 | char uid[8]; 174 | char connected_uid[8]; 175 | char position; 176 | uint8_t hardware_version[3]; 177 | uint8_t firmware_version[3]; 178 | uint16_t device_identifier; 179 | } ATTRIBUTE_PACKED GetIdentityResponse_; 180 | 181 | #if defined _MSC_VER || defined __BORLANDC__ 182 | #pragma pack(pop) 183 | #endif 184 | #undef ATTRIBUTE_PACKED 185 | 186 | static void accelerometer_callback_wrapper_acceleration(DevicePrivate *device_p, Packet *packet) { 187 | AccelerationCallbackFunction callback_function; 188 | void *user_data = device_p->registered_callback_user_data[ACCELEROMETER_CALLBACK_ACCELERATION]; 189 | AccelerationCallback_ *callback = (AccelerationCallback_ *)packet; 190 | *(void **)(&callback_function) = device_p->registered_callbacks[ACCELEROMETER_CALLBACK_ACCELERATION]; 191 | 192 | if (callback_function == NULL) { 193 | return; 194 | } 195 | 196 | callback->x = leconvert_int16_from(callback->x); 197 | callback->y = leconvert_int16_from(callback->y); 198 | callback->z = leconvert_int16_from(callback->z); 199 | 200 | callback_function(callback->x, callback->y, callback->z, user_data); 201 | } 202 | 203 | static void accelerometer_callback_wrapper_acceleration_reached(DevicePrivate *device_p, Packet *packet) { 204 | AccelerationReachedCallbackFunction callback_function; 205 | void *user_data = device_p->registered_callback_user_data[ACCELEROMETER_CALLBACK_ACCELERATION_REACHED]; 206 | AccelerationReachedCallback_ *callback = (AccelerationReachedCallback_ *)packet; 207 | *(void **)(&callback_function) = device_p->registered_callbacks[ACCELEROMETER_CALLBACK_ACCELERATION_REACHED]; 208 | 209 | if (callback_function == NULL) { 210 | return; 211 | } 212 | 213 | callback->x = leconvert_int16_from(callback->x); 214 | callback->y = leconvert_int16_from(callback->y); 215 | callback->z = leconvert_int16_from(callback->z); 216 | 217 | callback_function(callback->x, callback->y, callback->z, user_data); 218 | } 219 | 220 | void accelerometer_create(Accelerometer *accelerometer, const char *uid, IPConnection *ipcon) { 221 | DevicePrivate *device_p; 222 | 223 | device_create(accelerometer, uid, ipcon->p, 2, 0, 1); 224 | 225 | device_p = accelerometer->p; 226 | 227 | device_p->response_expected[ACCELEROMETER_FUNCTION_GET_ACCELERATION] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 228 | device_p->response_expected[ACCELEROMETER_FUNCTION_SET_ACCELERATION_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_TRUE; 229 | device_p->response_expected[ACCELEROMETER_FUNCTION_GET_ACCELERATION_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 230 | device_p->response_expected[ACCELEROMETER_FUNCTION_SET_ACCELERATION_CALLBACK_THRESHOLD] = DEVICE_RESPONSE_EXPECTED_TRUE; 231 | device_p->response_expected[ACCELEROMETER_FUNCTION_GET_ACCELERATION_CALLBACK_THRESHOLD] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 232 | device_p->response_expected[ACCELEROMETER_FUNCTION_SET_DEBOUNCE_PERIOD] = DEVICE_RESPONSE_EXPECTED_TRUE; 233 | device_p->response_expected[ACCELEROMETER_FUNCTION_GET_DEBOUNCE_PERIOD] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 234 | device_p->response_expected[ACCELEROMETER_FUNCTION_GET_TEMPERATURE] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 235 | device_p->response_expected[ACCELEROMETER_FUNCTION_SET_CONFIGURATION] = DEVICE_RESPONSE_EXPECTED_FALSE; 236 | device_p->response_expected[ACCELEROMETER_FUNCTION_GET_CONFIGURATION] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 237 | device_p->response_expected[ACCELEROMETER_FUNCTION_LED_ON] = DEVICE_RESPONSE_EXPECTED_FALSE; 238 | device_p->response_expected[ACCELEROMETER_FUNCTION_LED_OFF] = DEVICE_RESPONSE_EXPECTED_FALSE; 239 | device_p->response_expected[ACCELEROMETER_FUNCTION_IS_LED_ON] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 240 | device_p->response_expected[ACCELEROMETER_CALLBACK_ACCELERATION] = DEVICE_RESPONSE_EXPECTED_ALWAYS_FALSE; 241 | device_p->response_expected[ACCELEROMETER_CALLBACK_ACCELERATION_REACHED] = DEVICE_RESPONSE_EXPECTED_ALWAYS_FALSE; 242 | device_p->response_expected[ACCELEROMETER_FUNCTION_GET_IDENTITY] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 243 | 244 | device_p->callback_wrappers[ACCELEROMETER_CALLBACK_ACCELERATION] = accelerometer_callback_wrapper_acceleration; 245 | device_p->callback_wrappers[ACCELEROMETER_CALLBACK_ACCELERATION_REACHED] = accelerometer_callback_wrapper_acceleration_reached; 246 | } 247 | 248 | void accelerometer_destroy(Accelerometer *accelerometer) { 249 | device_release(accelerometer->p); 250 | } 251 | 252 | int accelerometer_get_response_expected(Accelerometer *accelerometer, uint8_t function_id, bool *ret_response_expected) { 253 | return device_get_response_expected(accelerometer->p, function_id, ret_response_expected); 254 | } 255 | 256 | int accelerometer_set_response_expected(Accelerometer *accelerometer, uint8_t function_id, bool response_expected) { 257 | return device_set_response_expected(accelerometer->p, function_id, response_expected); 258 | } 259 | 260 | int accelerometer_set_response_expected_all(Accelerometer *accelerometer, bool response_expected) { 261 | return device_set_response_expected_all(accelerometer->p, response_expected); 262 | } 263 | 264 | void accelerometer_register_callback(Accelerometer *accelerometer, uint8_t id, void *callback, void *user_data) { 265 | device_register_callback(accelerometer->p, id, callback, user_data); 266 | } 267 | 268 | int accelerometer_get_api_version(Accelerometer *accelerometer, uint8_t ret_api_version[3]) { 269 | return device_get_api_version(accelerometer->p, ret_api_version); 270 | } 271 | 272 | int accelerometer_get_acceleration(Accelerometer *accelerometer, int16_t *ret_x, int16_t *ret_y, int16_t *ret_z) { 273 | DevicePrivate *device_p = accelerometer->p; 274 | GetAcceleration_ request; 275 | GetAccelerationResponse_ response; 276 | int ret; 277 | 278 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_GET_ACCELERATION, device_p->ipcon_p, device_p); 279 | 280 | if (ret < 0) { 281 | return ret; 282 | } 283 | 284 | 285 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 286 | 287 | if (ret < 0) { 288 | return ret; 289 | } 290 | *ret_x = leconvert_int16_from(response.x); 291 | *ret_y = leconvert_int16_from(response.y); 292 | *ret_z = leconvert_int16_from(response.z); 293 | 294 | 295 | 296 | return ret; 297 | } 298 | 299 | int accelerometer_set_acceleration_callback_period(Accelerometer *accelerometer, uint32_t period) { 300 | DevicePrivate *device_p = accelerometer->p; 301 | SetAccelerationCallbackPeriod_ request; 302 | int ret; 303 | 304 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_SET_ACCELERATION_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 305 | 306 | if (ret < 0) { 307 | return ret; 308 | } 309 | 310 | request.period = leconvert_uint32_to(period); 311 | 312 | ret = device_send_request(device_p, (Packet *)&request, NULL); 313 | 314 | 315 | return ret; 316 | } 317 | 318 | int accelerometer_get_acceleration_callback_period(Accelerometer *accelerometer, uint32_t *ret_period) { 319 | DevicePrivate *device_p = accelerometer->p; 320 | GetAccelerationCallbackPeriod_ request; 321 | GetAccelerationCallbackPeriodResponse_ response; 322 | int ret; 323 | 324 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_GET_ACCELERATION_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 325 | 326 | if (ret < 0) { 327 | return ret; 328 | } 329 | 330 | 331 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 332 | 333 | if (ret < 0) { 334 | return ret; 335 | } 336 | *ret_period = leconvert_uint32_from(response.period); 337 | 338 | 339 | 340 | return ret; 341 | } 342 | 343 | int accelerometer_set_acceleration_callback_threshold(Accelerometer *accelerometer, char option, int16_t min_x, int16_t max_x, int16_t min_y, int16_t max_y, int16_t min_z, int16_t max_z) { 344 | DevicePrivate *device_p = accelerometer->p; 345 | SetAccelerationCallbackThreshold_ request; 346 | int ret; 347 | 348 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_SET_ACCELERATION_CALLBACK_THRESHOLD, device_p->ipcon_p, device_p); 349 | 350 | if (ret < 0) { 351 | return ret; 352 | } 353 | 354 | request.option = option; 355 | request.min_x = leconvert_int16_to(min_x); 356 | request.max_x = leconvert_int16_to(max_x); 357 | request.min_y = leconvert_int16_to(min_y); 358 | request.max_y = leconvert_int16_to(max_y); 359 | request.min_z = leconvert_int16_to(min_z); 360 | request.max_z = leconvert_int16_to(max_z); 361 | 362 | ret = device_send_request(device_p, (Packet *)&request, NULL); 363 | 364 | 365 | return ret; 366 | } 367 | 368 | int accelerometer_get_acceleration_callback_threshold(Accelerometer *accelerometer, char *ret_option, int16_t *ret_min_x, int16_t *ret_max_x, int16_t *ret_min_y, int16_t *ret_max_y, int16_t *ret_min_z, int16_t *ret_max_z) { 369 | DevicePrivate *device_p = accelerometer->p; 370 | GetAccelerationCallbackThreshold_ request; 371 | GetAccelerationCallbackThresholdResponse_ response; 372 | int ret; 373 | 374 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_GET_ACCELERATION_CALLBACK_THRESHOLD, device_p->ipcon_p, device_p); 375 | 376 | if (ret < 0) { 377 | return ret; 378 | } 379 | 380 | 381 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 382 | 383 | if (ret < 0) { 384 | return ret; 385 | } 386 | *ret_option = response.option; 387 | *ret_min_x = leconvert_int16_from(response.min_x); 388 | *ret_max_x = leconvert_int16_from(response.max_x); 389 | *ret_min_y = leconvert_int16_from(response.min_y); 390 | *ret_max_y = leconvert_int16_from(response.max_y); 391 | *ret_min_z = leconvert_int16_from(response.min_z); 392 | *ret_max_z = leconvert_int16_from(response.max_z); 393 | 394 | 395 | 396 | return ret; 397 | } 398 | 399 | int accelerometer_set_debounce_period(Accelerometer *accelerometer, uint32_t debounce) { 400 | DevicePrivate *device_p = accelerometer->p; 401 | SetDebouncePeriod_ request; 402 | int ret; 403 | 404 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_SET_DEBOUNCE_PERIOD, device_p->ipcon_p, device_p); 405 | 406 | if (ret < 0) { 407 | return ret; 408 | } 409 | 410 | request.debounce = leconvert_uint32_to(debounce); 411 | 412 | ret = device_send_request(device_p, (Packet *)&request, NULL); 413 | 414 | 415 | return ret; 416 | } 417 | 418 | int accelerometer_get_debounce_period(Accelerometer *accelerometer, uint32_t *ret_debounce) { 419 | DevicePrivate *device_p = accelerometer->p; 420 | GetDebouncePeriod_ request; 421 | GetDebouncePeriodResponse_ response; 422 | int ret; 423 | 424 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_GET_DEBOUNCE_PERIOD, device_p->ipcon_p, device_p); 425 | 426 | if (ret < 0) { 427 | return ret; 428 | } 429 | 430 | 431 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 432 | 433 | if (ret < 0) { 434 | return ret; 435 | } 436 | *ret_debounce = leconvert_uint32_from(response.debounce); 437 | 438 | 439 | 440 | return ret; 441 | } 442 | 443 | int accelerometer_get_temperature(Accelerometer *accelerometer, int16_t *ret_temperature) { 444 | DevicePrivate *device_p = accelerometer->p; 445 | GetTemperature_ request; 446 | GetTemperatureResponse_ response; 447 | int ret; 448 | 449 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_GET_TEMPERATURE, device_p->ipcon_p, device_p); 450 | 451 | if (ret < 0) { 452 | return ret; 453 | } 454 | 455 | 456 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 457 | 458 | if (ret < 0) { 459 | return ret; 460 | } 461 | *ret_temperature = leconvert_int16_from(response.temperature); 462 | 463 | 464 | 465 | return ret; 466 | } 467 | 468 | int accelerometer_set_configuration(Accelerometer *accelerometer, uint8_t data_rate, uint8_t full_scale, uint8_t filter_bandwidth) { 469 | DevicePrivate *device_p = accelerometer->p; 470 | SetConfiguration_ request; 471 | int ret; 472 | 473 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_SET_CONFIGURATION, device_p->ipcon_p, device_p); 474 | 475 | if (ret < 0) { 476 | return ret; 477 | } 478 | 479 | request.data_rate = data_rate; 480 | request.full_scale = full_scale; 481 | request.filter_bandwidth = filter_bandwidth; 482 | 483 | ret = device_send_request(device_p, (Packet *)&request, NULL); 484 | 485 | 486 | return ret; 487 | } 488 | 489 | int accelerometer_get_configuration(Accelerometer *accelerometer, uint8_t *ret_data_rate, uint8_t *ret_full_scale, uint8_t *ret_filter_bandwidth) { 490 | DevicePrivate *device_p = accelerometer->p; 491 | GetConfiguration_ request; 492 | GetConfigurationResponse_ response; 493 | int ret; 494 | 495 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_GET_CONFIGURATION, device_p->ipcon_p, device_p); 496 | 497 | if (ret < 0) { 498 | return ret; 499 | } 500 | 501 | 502 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 503 | 504 | if (ret < 0) { 505 | return ret; 506 | } 507 | *ret_data_rate = response.data_rate; 508 | *ret_full_scale = response.full_scale; 509 | *ret_filter_bandwidth = response.filter_bandwidth; 510 | 511 | 512 | 513 | return ret; 514 | } 515 | 516 | int accelerometer_led_on(Accelerometer *accelerometer) { 517 | DevicePrivate *device_p = accelerometer->p; 518 | LEDOn_ request; 519 | int ret; 520 | 521 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_LED_ON, device_p->ipcon_p, device_p); 522 | 523 | if (ret < 0) { 524 | return ret; 525 | } 526 | 527 | 528 | ret = device_send_request(device_p, (Packet *)&request, NULL); 529 | 530 | 531 | return ret; 532 | } 533 | 534 | int accelerometer_led_off(Accelerometer *accelerometer) { 535 | DevicePrivate *device_p = accelerometer->p; 536 | LEDOff_ request; 537 | int ret; 538 | 539 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_LED_OFF, device_p->ipcon_p, device_p); 540 | 541 | if (ret < 0) { 542 | return ret; 543 | } 544 | 545 | 546 | ret = device_send_request(device_p, (Packet *)&request, NULL); 547 | 548 | 549 | return ret; 550 | } 551 | 552 | int accelerometer_is_led_on(Accelerometer *accelerometer, bool *ret_on) { 553 | DevicePrivate *device_p = accelerometer->p; 554 | IsLEDOn_ request; 555 | IsLEDOnResponse_ response; 556 | int ret; 557 | 558 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_IS_LED_ON, device_p->ipcon_p, device_p); 559 | 560 | if (ret < 0) { 561 | return ret; 562 | } 563 | 564 | 565 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 566 | 567 | if (ret < 0) { 568 | return ret; 569 | } 570 | *ret_on = response.on; 571 | 572 | 573 | 574 | return ret; 575 | } 576 | 577 | int accelerometer_get_identity(Accelerometer *accelerometer, char ret_uid[8], char ret_connected_uid[8], char *ret_position, uint8_t ret_hardware_version[3], uint8_t ret_firmware_version[3], uint16_t *ret_device_identifier) { 578 | DevicePrivate *device_p = accelerometer->p; 579 | GetIdentity_ request; 580 | GetIdentityResponse_ response; 581 | int ret; 582 | 583 | ret = packet_header_create(&request.header, sizeof(request), ACCELEROMETER_FUNCTION_GET_IDENTITY, device_p->ipcon_p, device_p); 584 | 585 | if (ret < 0) { 586 | return ret; 587 | } 588 | 589 | 590 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 591 | 592 | if (ret < 0) { 593 | return ret; 594 | } 595 | memcpy(ret_uid, response.uid, 8); 596 | memcpy(ret_connected_uid, response.connected_uid, 8); 597 | *ret_position = response.position; 598 | memcpy(ret_hardware_version, response.hardware_version, 3 * sizeof(uint8_t)); 599 | memcpy(ret_firmware_version, response.firmware_version, 3 * sizeof(uint8_t)); 600 | *ret_device_identifier = leconvert_uint16_from(response.device_identifier); 601 | 602 | 603 | 604 | return ret; 605 | } 606 | 607 | #ifdef __cplusplus 608 | } 609 | #endif 610 | -------------------------------------------------------------------------------- /Sensors/bricklet_gps.cpp: -------------------------------------------------------------------------------- 1 | /* *********************************************************** 2 | * This file was automatically generated on 2016-09-08. * 3 | * * 4 | * C/C++ Bindings Version 2.1.12 * 5 | * * 6 | * If you have a bugfix for this file and want to commit it, * 7 | * please fix the bug in the generator. You can find a link * 8 | * to the generators git repository on tinkerforge.com * 9 | *************************************************************/ 10 | 11 | 12 | #define IPCON_EXPOSE_INTERNALS 13 | 14 | #include "bricklet_gps.h" 15 | 16 | #include 17 | 18 | #ifdef __cplusplus 19 | extern "C" { 20 | #endif 21 | 22 | 23 | 24 | typedef void (*CoordinatesCallbackFunction)(uint32_t, char, uint32_t, char, uint16_t, uint16_t, uint16_t, uint16_t, void *); 25 | 26 | typedef void (*StatusCallbackFunction)(uint8_t, uint8_t, uint8_t, void *); 27 | 28 | typedef void (*AltitudeCallbackFunction)(int32_t, int32_t, void *); 29 | 30 | typedef void (*MotionCallbackFunction)(uint32_t, uint32_t, void *); 31 | 32 | typedef void (*DateTimeCallbackFunction)(uint32_t, uint32_t, void *); 33 | 34 | #if defined _MSC_VER || defined __BORLANDC__ 35 | #pragma pack(push) 36 | #pragma pack(1) 37 | #define ATTRIBUTE_PACKED 38 | #elif defined __GNUC__ 39 | #ifdef _WIN32 40 | // workaround struct packing bug in GCC 4.7 on Windows 41 | // http://gcc.gnu.org/bugzilla/show_bug.cgi?id=52991 42 | #define ATTRIBUTE_PACKED __attribute__((gcc_struct, packed)) 43 | #else 44 | #define ATTRIBUTE_PACKED __attribute__((packed)) 45 | #endif 46 | #else 47 | #error unknown compiler, do not know how to enable struct packing 48 | #endif 49 | 50 | typedef struct { 51 | PacketHeader header; 52 | } ATTRIBUTE_PACKED GetCoordinates_; 53 | 54 | typedef struct { 55 | PacketHeader header; 56 | uint32_t latitude; 57 | char ns; 58 | uint32_t longitude; 59 | char ew; 60 | uint16_t pdop; 61 | uint16_t hdop; 62 | uint16_t vdop; 63 | uint16_t epe; 64 | } ATTRIBUTE_PACKED GetCoordinatesResponse_; 65 | 66 | typedef struct { 67 | PacketHeader header; 68 | } ATTRIBUTE_PACKED GetStatus_; 69 | 70 | typedef struct { 71 | PacketHeader header; 72 | uint8_t fix; 73 | uint8_t satellites_view; 74 | uint8_t satellites_used; 75 | } ATTRIBUTE_PACKED GetStatusResponse_; 76 | 77 | typedef struct { 78 | PacketHeader header; 79 | } ATTRIBUTE_PACKED GetAltitude_; 80 | 81 | typedef struct { 82 | PacketHeader header; 83 | int32_t altitude; 84 | int32_t geoidal_separation; 85 | } ATTRIBUTE_PACKED GetAltitudeResponse_; 86 | 87 | typedef struct { 88 | PacketHeader header; 89 | } ATTRIBUTE_PACKED GetMotion_; 90 | 91 | typedef struct { 92 | PacketHeader header; 93 | uint32_t course; 94 | uint32_t speed; 95 | } ATTRIBUTE_PACKED GetMotionResponse_; 96 | 97 | typedef struct { 98 | PacketHeader header; 99 | } ATTRIBUTE_PACKED GetDateTime_; 100 | 101 | typedef struct { 102 | PacketHeader header; 103 | uint32_t date; 104 | uint32_t time; 105 | } ATTRIBUTE_PACKED GetDateTimeResponse_; 106 | 107 | typedef struct { 108 | PacketHeader header; 109 | uint8_t restart_type; 110 | } ATTRIBUTE_PACKED Restart_; 111 | 112 | typedef struct { 113 | PacketHeader header; 114 | uint32_t period; 115 | } ATTRIBUTE_PACKED SetCoordinatesCallbackPeriod_; 116 | 117 | typedef struct { 118 | PacketHeader header; 119 | } ATTRIBUTE_PACKED GetCoordinatesCallbackPeriod_; 120 | 121 | typedef struct { 122 | PacketHeader header; 123 | uint32_t period; 124 | } ATTRIBUTE_PACKED GetCoordinatesCallbackPeriodResponse_; 125 | 126 | typedef struct { 127 | PacketHeader header; 128 | uint32_t period; 129 | } ATTRIBUTE_PACKED SetStatusCallbackPeriod_; 130 | 131 | typedef struct { 132 | PacketHeader header; 133 | } ATTRIBUTE_PACKED GetStatusCallbackPeriod_; 134 | 135 | typedef struct { 136 | PacketHeader header; 137 | uint32_t period; 138 | } ATTRIBUTE_PACKED GetStatusCallbackPeriodResponse_; 139 | 140 | typedef struct { 141 | PacketHeader header; 142 | uint32_t period; 143 | } ATTRIBUTE_PACKED SetAltitudeCallbackPeriod_; 144 | 145 | typedef struct { 146 | PacketHeader header; 147 | } ATTRIBUTE_PACKED GetAltitudeCallbackPeriod_; 148 | 149 | typedef struct { 150 | PacketHeader header; 151 | uint32_t period; 152 | } ATTRIBUTE_PACKED GetAltitudeCallbackPeriodResponse_; 153 | 154 | typedef struct { 155 | PacketHeader header; 156 | uint32_t period; 157 | } ATTRIBUTE_PACKED SetMotionCallbackPeriod_; 158 | 159 | typedef struct { 160 | PacketHeader header; 161 | } ATTRIBUTE_PACKED GetMotionCallbackPeriod_; 162 | 163 | typedef struct { 164 | PacketHeader header; 165 | uint32_t period; 166 | } ATTRIBUTE_PACKED GetMotionCallbackPeriodResponse_; 167 | 168 | typedef struct { 169 | PacketHeader header; 170 | uint32_t period; 171 | } ATTRIBUTE_PACKED SetDateTimeCallbackPeriod_; 172 | 173 | typedef struct { 174 | PacketHeader header; 175 | } ATTRIBUTE_PACKED GetDateTimeCallbackPeriod_; 176 | 177 | typedef struct { 178 | PacketHeader header; 179 | uint32_t period; 180 | } ATTRIBUTE_PACKED GetDateTimeCallbackPeriodResponse_; 181 | 182 | typedef struct { 183 | PacketHeader header; 184 | uint32_t latitude; 185 | char ns; 186 | uint32_t longitude; 187 | char ew; 188 | uint16_t pdop; 189 | uint16_t hdop; 190 | uint16_t vdop; 191 | uint16_t epe; 192 | } ATTRIBUTE_PACKED CoordinatesCallback_; 193 | 194 | typedef struct { 195 | PacketHeader header; 196 | uint8_t fix; 197 | uint8_t satellites_view; 198 | uint8_t satellites_used; 199 | } ATTRIBUTE_PACKED StatusCallback_; 200 | 201 | typedef struct { 202 | PacketHeader header; 203 | int32_t altitude; 204 | int32_t geoidal_separation; 205 | } ATTRIBUTE_PACKED AltitudeCallback_; 206 | 207 | typedef struct { 208 | PacketHeader header; 209 | uint32_t course; 210 | uint32_t speed; 211 | } ATTRIBUTE_PACKED MotionCallback_; 212 | 213 | typedef struct { 214 | PacketHeader header; 215 | uint32_t date; 216 | uint32_t time; 217 | } ATTRIBUTE_PACKED DateTimeCallback_; 218 | 219 | typedef struct { 220 | PacketHeader header; 221 | } ATTRIBUTE_PACKED GetIdentity_; 222 | 223 | typedef struct { 224 | PacketHeader header; 225 | char uid[8]; 226 | char connected_uid[8]; 227 | char position; 228 | uint8_t hardware_version[3]; 229 | uint8_t firmware_version[3]; 230 | uint16_t device_identifier; 231 | } ATTRIBUTE_PACKED GetIdentityResponse_; 232 | 233 | #if defined _MSC_VER || defined __BORLANDC__ 234 | #pragma pack(pop) 235 | #endif 236 | #undef ATTRIBUTE_PACKED 237 | 238 | static void gps_callback_wrapper_coordinates(DevicePrivate *device_p, Packet *packet) { 239 | CoordinatesCallbackFunction callback_function; 240 | void *user_data = device_p->registered_callback_user_data[GPS_CALLBACK_COORDINATES]; 241 | CoordinatesCallback_ *callback = (CoordinatesCallback_ *)packet; 242 | *(void **)(&callback_function) = device_p->registered_callbacks[GPS_CALLBACK_COORDINATES]; 243 | 244 | if (callback_function == NULL) { 245 | return; 246 | } 247 | 248 | callback->latitude = leconvert_uint32_from(callback->latitude); 249 | callback->longitude = leconvert_uint32_from(callback->longitude); 250 | callback->pdop = leconvert_uint16_from(callback->pdop); 251 | callback->hdop = leconvert_uint16_from(callback->hdop); 252 | callback->vdop = leconvert_uint16_from(callback->vdop); 253 | callback->epe = leconvert_uint16_from(callback->epe); 254 | 255 | callback_function(callback->latitude, callback->ns, callback->longitude, callback->ew, callback->pdop, callback->hdop, callback->vdop, callback->epe, user_data); 256 | } 257 | 258 | static void gps_callback_wrapper_status(DevicePrivate *device_p, Packet *packet) { 259 | StatusCallbackFunction callback_function; 260 | void *user_data = device_p->registered_callback_user_data[GPS_CALLBACK_STATUS]; 261 | StatusCallback_ *callback = (StatusCallback_ *)packet; 262 | *(void **)(&callback_function) = device_p->registered_callbacks[GPS_CALLBACK_STATUS]; 263 | 264 | if (callback_function == NULL) { 265 | return; 266 | } 267 | 268 | callback_function(callback->fix, callback->satellites_view, callback->satellites_used, user_data); 269 | } 270 | 271 | static void gps_callback_wrapper_altitude(DevicePrivate *device_p, Packet *packet) { 272 | AltitudeCallbackFunction callback_function; 273 | void *user_data = device_p->registered_callback_user_data[GPS_CALLBACK_ALTITUDE]; 274 | AltitudeCallback_ *callback = (AltitudeCallback_ *)packet; 275 | *(void **)(&callback_function) = device_p->registered_callbacks[GPS_CALLBACK_ALTITUDE]; 276 | 277 | if (callback_function == NULL) { 278 | return; 279 | } 280 | 281 | callback->altitude = leconvert_int32_from(callback->altitude); 282 | callback->geoidal_separation = leconvert_int32_from(callback->geoidal_separation); 283 | 284 | callback_function(callback->altitude, callback->geoidal_separation, user_data); 285 | } 286 | 287 | static void gps_callback_wrapper_motion(DevicePrivate *device_p, Packet *packet) { 288 | MotionCallbackFunction callback_function; 289 | void *user_data = device_p->registered_callback_user_data[GPS_CALLBACK_MOTION]; 290 | MotionCallback_ *callback = (MotionCallback_ *)packet; 291 | *(void **)(&callback_function) = device_p->registered_callbacks[GPS_CALLBACK_MOTION]; 292 | 293 | if (callback_function == NULL) { 294 | return; 295 | } 296 | 297 | callback->course = leconvert_uint32_from(callback->course); 298 | callback->speed = leconvert_uint32_from(callback->speed); 299 | 300 | callback_function(callback->course, callback->speed, user_data); 301 | } 302 | 303 | static void gps_callback_wrapper_date_time(DevicePrivate *device_p, Packet *packet) { 304 | DateTimeCallbackFunction callback_function; 305 | void *user_data = device_p->registered_callback_user_data[GPS_CALLBACK_DATE_TIME]; 306 | DateTimeCallback_ *callback = (DateTimeCallback_ *)packet; 307 | *(void **)(&callback_function) = device_p->registered_callbacks[GPS_CALLBACK_DATE_TIME]; 308 | 309 | if (callback_function == NULL) { 310 | return; 311 | } 312 | 313 | callback->date = leconvert_uint32_from(callback->date); 314 | callback->time = leconvert_uint32_from(callback->time); 315 | 316 | callback_function(callback->date, callback->time, user_data); 317 | } 318 | 319 | void gps_create(GPS *gps, const char *uid, IPConnection *ipcon) { 320 | DevicePrivate *device_p; 321 | 322 | device_create(gps, uid, ipcon->p, 2, 0, 1); 323 | 324 | device_p = gps->p; 325 | 326 | device_p->response_expected[GPS_FUNCTION_GET_COORDINATES] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 327 | device_p->response_expected[GPS_FUNCTION_GET_STATUS] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 328 | device_p->response_expected[GPS_FUNCTION_GET_ALTITUDE] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 329 | device_p->response_expected[GPS_FUNCTION_GET_MOTION] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 330 | device_p->response_expected[GPS_FUNCTION_GET_DATE_TIME] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 331 | device_p->response_expected[GPS_FUNCTION_RESTART] = DEVICE_RESPONSE_EXPECTED_FALSE; 332 | device_p->response_expected[GPS_FUNCTION_SET_COORDINATES_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_TRUE; 333 | device_p->response_expected[GPS_FUNCTION_GET_COORDINATES_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 334 | device_p->response_expected[GPS_FUNCTION_SET_STATUS_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_TRUE; 335 | device_p->response_expected[GPS_FUNCTION_GET_STATUS_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 336 | device_p->response_expected[GPS_FUNCTION_SET_ALTITUDE_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_TRUE; 337 | device_p->response_expected[GPS_FUNCTION_GET_ALTITUDE_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 338 | device_p->response_expected[GPS_FUNCTION_SET_MOTION_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_TRUE; 339 | device_p->response_expected[GPS_FUNCTION_GET_MOTION_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 340 | device_p->response_expected[GPS_FUNCTION_SET_DATE_TIME_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_TRUE; 341 | device_p->response_expected[GPS_FUNCTION_GET_DATE_TIME_CALLBACK_PERIOD] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 342 | device_p->response_expected[GPS_CALLBACK_COORDINATES] = DEVICE_RESPONSE_EXPECTED_ALWAYS_FALSE; 343 | device_p->response_expected[GPS_CALLBACK_STATUS] = DEVICE_RESPONSE_EXPECTED_ALWAYS_FALSE; 344 | device_p->response_expected[GPS_CALLBACK_ALTITUDE] = DEVICE_RESPONSE_EXPECTED_ALWAYS_FALSE; 345 | device_p->response_expected[GPS_CALLBACK_MOTION] = DEVICE_RESPONSE_EXPECTED_ALWAYS_FALSE; 346 | device_p->response_expected[GPS_CALLBACK_DATE_TIME] = DEVICE_RESPONSE_EXPECTED_ALWAYS_FALSE; 347 | device_p->response_expected[GPS_FUNCTION_GET_IDENTITY] = DEVICE_RESPONSE_EXPECTED_ALWAYS_TRUE; 348 | 349 | device_p->callback_wrappers[GPS_CALLBACK_COORDINATES] = gps_callback_wrapper_coordinates; 350 | device_p->callback_wrappers[GPS_CALLBACK_STATUS] = gps_callback_wrapper_status; 351 | device_p->callback_wrappers[GPS_CALLBACK_ALTITUDE] = gps_callback_wrapper_altitude; 352 | device_p->callback_wrappers[GPS_CALLBACK_MOTION] = gps_callback_wrapper_motion; 353 | device_p->callback_wrappers[GPS_CALLBACK_DATE_TIME] = gps_callback_wrapper_date_time; 354 | } 355 | 356 | void gps_destroy(GPS *gps) { 357 | device_release(gps->p); 358 | } 359 | 360 | int gps_get_response_expected(GPS *gps, uint8_t function_id, bool *ret_response_expected) { 361 | return device_get_response_expected(gps->p, function_id, ret_response_expected); 362 | } 363 | 364 | int gps_set_response_expected(GPS *gps, uint8_t function_id, bool response_expected) { 365 | return device_set_response_expected(gps->p, function_id, response_expected); 366 | } 367 | 368 | int gps_set_response_expected_all(GPS *gps, bool response_expected) { 369 | return device_set_response_expected_all(gps->p, response_expected); 370 | } 371 | 372 | void gps_register_callback(GPS *gps, uint8_t id, void *callback, void *user_data) { 373 | device_register_callback(gps->p, id, callback, user_data); 374 | } 375 | 376 | int gps_get_api_version(GPS *gps, uint8_t ret_api_version[3]) { 377 | return device_get_api_version(gps->p, ret_api_version); 378 | } 379 | 380 | int gps_get_coordinates(GPS *gps, uint32_t *ret_latitude, char *ret_ns, uint32_t *ret_longitude, char *ret_ew, uint16_t *ret_pdop, uint16_t *ret_hdop, uint16_t *ret_vdop, uint16_t *ret_epe) { 381 | DevicePrivate *device_p = gps->p; 382 | GetCoordinates_ request; 383 | GetCoordinatesResponse_ response; 384 | int ret; 385 | 386 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_GET_COORDINATES, device_p->ipcon_p, device_p); 387 | 388 | if (ret < 0) { 389 | return ret; 390 | } 391 | 392 | 393 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 394 | 395 | if (ret < 0) { 396 | return ret; 397 | } 398 | *ret_latitude = leconvert_uint32_from(response.latitude); 399 | *ret_ns = response.ns; 400 | *ret_longitude = leconvert_uint32_from(response.longitude); 401 | *ret_ew = response.ew; 402 | *ret_pdop = leconvert_uint16_from(response.pdop); 403 | *ret_hdop = leconvert_uint16_from(response.hdop); 404 | *ret_vdop = leconvert_uint16_from(response.vdop); 405 | *ret_epe = leconvert_uint16_from(response.epe); 406 | 407 | 408 | 409 | return ret; 410 | } 411 | 412 | int gps_get_status(GPS *gps, uint8_t *ret_fix, uint8_t *ret_satellites_view, uint8_t *ret_satellites_used) { 413 | DevicePrivate *device_p = gps->p; 414 | GetStatus_ request; 415 | GetStatusResponse_ response; 416 | int ret; 417 | 418 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_GET_STATUS, device_p->ipcon_p, device_p); 419 | 420 | if (ret < 0) { 421 | return ret; 422 | } 423 | 424 | 425 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 426 | 427 | if (ret < 0) { 428 | return ret; 429 | } 430 | *ret_fix = response.fix; 431 | *ret_satellites_view = response.satellites_view; 432 | *ret_satellites_used = response.satellites_used; 433 | 434 | 435 | 436 | return ret; 437 | } 438 | 439 | int gps_get_altitude(GPS *gps, int32_t *ret_altitude, int32_t *ret_geoidal_separation) { 440 | DevicePrivate *device_p = gps->p; 441 | GetAltitude_ request; 442 | GetAltitudeResponse_ response; 443 | int ret; 444 | 445 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_GET_ALTITUDE, device_p->ipcon_p, device_p); 446 | 447 | if (ret < 0) { 448 | return ret; 449 | } 450 | 451 | 452 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 453 | 454 | if (ret < 0) { 455 | return ret; 456 | } 457 | *ret_altitude = leconvert_int32_from(response.altitude); 458 | *ret_geoidal_separation = leconvert_int32_from(response.geoidal_separation); 459 | 460 | 461 | 462 | return ret; 463 | } 464 | 465 | int gps_get_motion(GPS *gps, uint32_t *ret_course, uint32_t *ret_speed) { 466 | DevicePrivate *device_p = gps->p; 467 | GetMotion_ request; 468 | GetMotionResponse_ response; 469 | int ret; 470 | 471 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_GET_MOTION, device_p->ipcon_p, device_p); 472 | 473 | if (ret < 0) { 474 | return ret; 475 | } 476 | 477 | 478 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 479 | 480 | if (ret < 0) { 481 | return ret; 482 | } 483 | *ret_course = leconvert_uint32_from(response.course); 484 | *ret_speed = leconvert_uint32_from(response.speed); 485 | 486 | 487 | 488 | return ret; 489 | } 490 | 491 | int gps_get_date_time(GPS *gps, uint32_t *ret_date, uint32_t *ret_time) { 492 | DevicePrivate *device_p = gps->p; 493 | GetDateTime_ request; 494 | GetDateTimeResponse_ response; 495 | int ret; 496 | 497 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_GET_DATE_TIME, device_p->ipcon_p, device_p); 498 | 499 | if (ret < 0) { 500 | return ret; 501 | } 502 | 503 | 504 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 505 | 506 | if (ret < 0) { 507 | return ret; 508 | } 509 | *ret_date = leconvert_uint32_from(response.date); 510 | *ret_time = leconvert_uint32_from(response.time); 511 | 512 | 513 | 514 | return ret; 515 | } 516 | 517 | int gps_restart(GPS *gps, uint8_t restart_type) { 518 | DevicePrivate *device_p = gps->p; 519 | Restart_ request; 520 | int ret; 521 | 522 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_RESTART, device_p->ipcon_p, device_p); 523 | 524 | if (ret < 0) { 525 | return ret; 526 | } 527 | 528 | request.restart_type = restart_type; 529 | 530 | ret = device_send_request(device_p, (Packet *)&request, NULL); 531 | 532 | 533 | return ret; 534 | } 535 | 536 | int gps_set_coordinates_callback_period(GPS *gps, uint32_t period) { 537 | DevicePrivate *device_p = gps->p; 538 | SetCoordinatesCallbackPeriod_ request; 539 | int ret; 540 | 541 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_SET_COORDINATES_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 542 | 543 | if (ret < 0) { 544 | return ret; 545 | } 546 | 547 | request.period = leconvert_uint32_to(period); 548 | 549 | ret = device_send_request(device_p, (Packet *)&request, NULL); 550 | 551 | 552 | return ret; 553 | } 554 | 555 | int gps_get_coordinates_callback_period(GPS *gps, uint32_t *ret_period) { 556 | DevicePrivate *device_p = gps->p; 557 | GetCoordinatesCallbackPeriod_ request; 558 | GetCoordinatesCallbackPeriodResponse_ response; 559 | int ret; 560 | 561 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_GET_COORDINATES_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 562 | 563 | if (ret < 0) { 564 | return ret; 565 | } 566 | 567 | 568 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 569 | 570 | if (ret < 0) { 571 | return ret; 572 | } 573 | *ret_period = leconvert_uint32_from(response.period); 574 | 575 | 576 | 577 | return ret; 578 | } 579 | 580 | int gps_set_status_callback_period(GPS *gps, uint32_t period) { 581 | DevicePrivate *device_p = gps->p; 582 | SetStatusCallbackPeriod_ request; 583 | int ret; 584 | 585 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_SET_STATUS_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 586 | 587 | if (ret < 0) { 588 | return ret; 589 | } 590 | 591 | request.period = leconvert_uint32_to(period); 592 | 593 | ret = device_send_request(device_p, (Packet *)&request, NULL); 594 | 595 | 596 | return ret; 597 | } 598 | 599 | int gps_get_status_callback_period(GPS *gps, uint32_t *ret_period) { 600 | DevicePrivate *device_p = gps->p; 601 | GetStatusCallbackPeriod_ request; 602 | GetStatusCallbackPeriodResponse_ response; 603 | int ret; 604 | 605 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_GET_STATUS_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 606 | 607 | if (ret < 0) { 608 | return ret; 609 | } 610 | 611 | 612 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 613 | 614 | if (ret < 0) { 615 | return ret; 616 | } 617 | *ret_period = leconvert_uint32_from(response.period); 618 | 619 | 620 | 621 | return ret; 622 | } 623 | 624 | int gps_set_altitude_callback_period(GPS *gps, uint32_t period) { 625 | DevicePrivate *device_p = gps->p; 626 | SetAltitudeCallbackPeriod_ request; 627 | int ret; 628 | 629 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_SET_ALTITUDE_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 630 | 631 | if (ret < 0) { 632 | return ret; 633 | } 634 | 635 | request.period = leconvert_uint32_to(period); 636 | 637 | ret = device_send_request(device_p, (Packet *)&request, NULL); 638 | 639 | 640 | return ret; 641 | } 642 | 643 | int gps_get_altitude_callback_period(GPS *gps, uint32_t *ret_period) { 644 | DevicePrivate *device_p = gps->p; 645 | GetAltitudeCallbackPeriod_ request; 646 | GetAltitudeCallbackPeriodResponse_ response; 647 | int ret; 648 | 649 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_GET_ALTITUDE_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 650 | 651 | if (ret < 0) { 652 | return ret; 653 | } 654 | 655 | 656 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 657 | 658 | if (ret < 0) { 659 | return ret; 660 | } 661 | *ret_period = leconvert_uint32_from(response.period); 662 | 663 | 664 | 665 | return ret; 666 | } 667 | 668 | int gps_set_motion_callback_period(GPS *gps, uint32_t period) { 669 | DevicePrivate *device_p = gps->p; 670 | SetMotionCallbackPeriod_ request; 671 | int ret; 672 | 673 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_SET_MOTION_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 674 | 675 | if (ret < 0) { 676 | return ret; 677 | } 678 | 679 | request.period = leconvert_uint32_to(period); 680 | 681 | ret = device_send_request(device_p, (Packet *)&request, NULL); 682 | 683 | 684 | return ret; 685 | } 686 | 687 | int gps_get_motion_callback_period(GPS *gps, uint32_t *ret_period) { 688 | DevicePrivate *device_p = gps->p; 689 | GetMotionCallbackPeriod_ request; 690 | GetMotionCallbackPeriodResponse_ response; 691 | int ret; 692 | 693 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_GET_MOTION_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 694 | 695 | if (ret < 0) { 696 | return ret; 697 | } 698 | 699 | 700 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 701 | 702 | if (ret < 0) { 703 | return ret; 704 | } 705 | *ret_period = leconvert_uint32_from(response.period); 706 | 707 | 708 | 709 | return ret; 710 | } 711 | 712 | int gps_set_date_time_callback_period(GPS *gps, uint32_t period) { 713 | DevicePrivate *device_p = gps->p; 714 | SetDateTimeCallbackPeriod_ request; 715 | int ret; 716 | 717 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_SET_DATE_TIME_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 718 | 719 | if (ret < 0) { 720 | return ret; 721 | } 722 | 723 | request.period = leconvert_uint32_to(period); 724 | 725 | ret = device_send_request(device_p, (Packet *)&request, NULL); 726 | 727 | 728 | return ret; 729 | } 730 | 731 | int gps_get_date_time_callback_period(GPS *gps, uint32_t *ret_period) { 732 | DevicePrivate *device_p = gps->p; 733 | GetDateTimeCallbackPeriod_ request; 734 | GetDateTimeCallbackPeriodResponse_ response; 735 | int ret; 736 | 737 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_GET_DATE_TIME_CALLBACK_PERIOD, device_p->ipcon_p, device_p); 738 | 739 | if (ret < 0) { 740 | return ret; 741 | } 742 | 743 | 744 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 745 | 746 | if (ret < 0) { 747 | return ret; 748 | } 749 | *ret_period = leconvert_uint32_from(response.period); 750 | 751 | 752 | 753 | return ret; 754 | } 755 | 756 | int gps_get_identity(GPS *gps, char ret_uid[8], char ret_connected_uid[8], char *ret_position, uint8_t ret_hardware_version[3], uint8_t ret_firmware_version[3], uint16_t *ret_device_identifier) { 757 | DevicePrivate *device_p = gps->p; 758 | GetIdentity_ request; 759 | GetIdentityResponse_ response; 760 | int ret; 761 | 762 | ret = packet_header_create(&request.header, sizeof(request), GPS_FUNCTION_GET_IDENTITY, device_p->ipcon_p, device_p); 763 | 764 | if (ret < 0) { 765 | return ret; 766 | } 767 | 768 | 769 | ret = device_send_request(device_p, (Packet *)&request, (Packet *)&response); 770 | 771 | if (ret < 0) { 772 | return ret; 773 | } 774 | memcpy(ret_uid, response.uid, 8); 775 | memcpy(ret_connected_uid, response.connected_uid, 8); 776 | *ret_position = response.position; 777 | memcpy(ret_hardware_version, response.hardware_version, 3 * sizeof(uint8_t)); 778 | memcpy(ret_firmware_version, response.firmware_version, 3 * sizeof(uint8_t)); 779 | *ret_device_identifier = leconvert_uint16_from(response.device_identifier); 780 | 781 | 782 | 783 | return ret; 784 | } 785 | 786 | #ifdef __cplusplus 787 | } 788 | #endif 789 | -------------------------------------------------------------------------------- /Sensors/brick_imu_v2.h: -------------------------------------------------------------------------------- 1 | /* *********************************************************** 2 | * This file was automatically generated on 2016-09-08. * 3 | * * 4 | * C/C++ Bindings Version 2.1.12 * 5 | * * 6 | * If you have a bugfix for this file and want to commit it, * 7 | * please fix the bug in the generator. You can find a link * 8 | * to the generators git repository on tinkerforge.com * 9 | *************************************************************/ 10 | 11 | #ifndef BRICK_IMU_V2_H 12 | #define BRICK_IMU_V2_H 13 | 14 | #include "ip_connection.h" 15 | 16 | #ifdef __cplusplus 17 | extern "C" { 18 | #endif 19 | 20 | /** 21 | * \defgroup BrickIMUV2 IMU Brick 2.0 22 | */ 23 | 24 | /** 25 | * \ingroup BrickIMUV2 26 | * 27 | * Full fledged AHRS with 9 degrees of freedom 28 | */ 29 | typedef Device IMUV2; 30 | 31 | /** 32 | * \ingroup BrickIMUV2 33 | */ 34 | #define IMU_V2_FUNCTION_GET_ACCELERATION 1 35 | 36 | /** 37 | * \ingroup BrickIMUV2 38 | */ 39 | #define IMU_V2_FUNCTION_GET_MAGNETIC_FIELD 2 40 | 41 | /** 42 | * \ingroup BrickIMUV2 43 | */ 44 | #define IMU_V2_FUNCTION_GET_ANGULAR_VELOCITY 3 45 | 46 | /** 47 | * \ingroup BrickIMUV2 48 | */ 49 | #define IMU_V2_FUNCTION_GET_TEMPERATURE 4 50 | 51 | /** 52 | * \ingroup BrickIMUV2 53 | */ 54 | #define IMU_V2_FUNCTION_GET_ORIENTATION 5 55 | 56 | /** 57 | * \ingroup BrickIMUV2 58 | */ 59 | #define IMU_V2_FUNCTION_GET_LINEAR_ACCELERATION 6 60 | 61 | /** 62 | * \ingroup BrickIMUV2 63 | */ 64 | #define IMU_V2_FUNCTION_GET_GRAVITY_VECTOR 7 65 | 66 | /** 67 | * \ingroup BrickIMUV2 68 | */ 69 | #define IMU_V2_FUNCTION_GET_QUATERNION 8 70 | 71 | /** 72 | * \ingroup BrickIMUV2 73 | */ 74 | #define IMU_V2_FUNCTION_GET_ALL_DATA 9 75 | 76 | /** 77 | * \ingroup BrickIMUV2 78 | */ 79 | #define IMU_V2_FUNCTION_LEDS_ON 10 80 | 81 | /** 82 | * \ingroup BrickIMUV2 83 | */ 84 | #define IMU_V2_FUNCTION_LEDS_OFF 11 85 | 86 | /** 87 | * \ingroup BrickIMUV2 88 | */ 89 | #define IMU_V2_FUNCTION_ARE_LEDS_ON 12 90 | 91 | /** 92 | * \ingroup BrickIMUV2 93 | */ 94 | #define IMU_V2_FUNCTION_SAVE_CALIBRATION 13 95 | 96 | /** 97 | * \ingroup BrickIMUV2 98 | */ 99 | #define IMU_V2_FUNCTION_SET_ACCELERATION_PERIOD 14 100 | 101 | /** 102 | * \ingroup BrickIMUV2 103 | */ 104 | #define IMU_V2_FUNCTION_GET_ACCELERATION_PERIOD 15 105 | 106 | /** 107 | * \ingroup BrickIMUV2 108 | */ 109 | #define IMU_V2_FUNCTION_SET_MAGNETIC_FIELD_PERIOD 16 110 | 111 | /** 112 | * \ingroup BrickIMUV2 113 | */ 114 | #define IMU_V2_FUNCTION_GET_MAGNETIC_FIELD_PERIOD 17 115 | 116 | /** 117 | * \ingroup BrickIMUV2 118 | */ 119 | #define IMU_V2_FUNCTION_SET_ANGULAR_VELOCITY_PERIOD 18 120 | 121 | /** 122 | * \ingroup BrickIMUV2 123 | */ 124 | #define IMU_V2_FUNCTION_GET_ANGULAR_VELOCITY_PERIOD 19 125 | 126 | /** 127 | * \ingroup BrickIMUV2 128 | */ 129 | #define IMU_V2_FUNCTION_SET_TEMPERATURE_PERIOD 20 130 | 131 | /** 132 | * \ingroup BrickIMUV2 133 | */ 134 | #define IMU_V2_FUNCTION_GET_TEMPERATURE_PERIOD 21 135 | 136 | /** 137 | * \ingroup BrickIMUV2 138 | */ 139 | #define IMU_V2_FUNCTION_SET_ORIENTATION_PERIOD 22 140 | 141 | /** 142 | * \ingroup BrickIMUV2 143 | */ 144 | #define IMU_V2_FUNCTION_GET_ORIENTATION_PERIOD 23 145 | 146 | /** 147 | * \ingroup BrickIMUV2 148 | */ 149 | #define IMU_V2_FUNCTION_SET_LINEAR_ACCELERATION_PERIOD 24 150 | 151 | /** 152 | * \ingroup BrickIMUV2 153 | */ 154 | #define IMU_V2_FUNCTION_GET_LINEAR_ACCELERATION_PERIOD 25 155 | 156 | /** 157 | * \ingroup BrickIMUV2 158 | */ 159 | #define IMU_V2_FUNCTION_SET_GRAVITY_VECTOR_PERIOD 26 160 | 161 | /** 162 | * \ingroup BrickIMUV2 163 | */ 164 | #define IMU_V2_FUNCTION_GET_GRAVITY_VECTOR_PERIOD 27 165 | 166 | /** 167 | * \ingroup BrickIMUV2 168 | */ 169 | #define IMU_V2_FUNCTION_SET_QUATERNION_PERIOD 28 170 | 171 | /** 172 | * \ingroup BrickIMUV2 173 | */ 174 | #define IMU_V2_FUNCTION_GET_QUATERNION_PERIOD 29 175 | 176 | /** 177 | * \ingroup BrickIMUV2 178 | */ 179 | #define IMU_V2_FUNCTION_SET_ALL_DATA_PERIOD 30 180 | 181 | /** 182 | * \ingroup BrickIMUV2 183 | */ 184 | #define IMU_V2_FUNCTION_GET_ALL_DATA_PERIOD 31 185 | 186 | /** 187 | * \ingroup BrickIMUV2 188 | */ 189 | #define IMU_V2_FUNCTION_ENABLE_STATUS_LED 238 190 | 191 | /** 192 | * \ingroup BrickIMUV2 193 | */ 194 | #define IMU_V2_FUNCTION_DISABLE_STATUS_LED 239 195 | 196 | /** 197 | * \ingroup BrickIMUV2 198 | */ 199 | #define IMU_V2_FUNCTION_IS_STATUS_LED_ENABLED 240 200 | 201 | /** 202 | * \ingroup BrickIMUV2 203 | */ 204 | #define IMU_V2_FUNCTION_GET_PROTOCOL1_BRICKLET_NAME 241 205 | 206 | /** 207 | * \ingroup BrickIMUV2 208 | */ 209 | #define IMU_V2_FUNCTION_GET_CHIP_TEMPERATURE 242 210 | 211 | /** 212 | * \ingroup BrickIMUV2 213 | */ 214 | #define IMU_V2_FUNCTION_RESET 243 215 | 216 | /** 217 | * \ingroup BrickIMUV2 218 | */ 219 | #define IMU_V2_FUNCTION_GET_IDENTITY 255 220 | 221 | /** 222 | * \ingroup BrickIMUV2 223 | * 224 | * Signature: \code void callback(int16_t x, int16_t y, int16_t z, void *user_data) \endcode 225 | * 226 | * This callback is triggered periodically with the period that is set by 227 | * {@link imu_v2_set_acceleration_period}. The parameters are the acceleration 228 | * for the x, y and z axis. 229 | */ 230 | #define IMU_V2_CALLBACK_ACCELERATION 32 231 | 232 | /** 233 | * \ingroup BrickIMUV2 234 | * 235 | * Signature: \code void callback(int16_t x, int16_t y, int16_t z, void *user_data) \endcode 236 | * 237 | * This callback is triggered periodically with the period that is set by 238 | * {@link imu_v2_set_magnetic_field_period}. The parameters are the magnetic field 239 | * for the x, y and z axis. 240 | */ 241 | #define IMU_V2_CALLBACK_MAGNETIC_FIELD 33 242 | 243 | /** 244 | * \ingroup BrickIMUV2 245 | * 246 | * Signature: \code void callback(int16_t x, int16_t y, int16_t z, void *user_data) \endcode 247 | * 248 | * This callback is triggered periodically with the period that is set by 249 | * {@link imu_v2_set_angular_velocity_period}. The parameters are the angular velocity 250 | * for the x, y and z axis. 251 | */ 252 | #define IMU_V2_CALLBACK_ANGULAR_VELOCITY 34 253 | 254 | /** 255 | * \ingroup BrickIMUV2 256 | * 257 | * Signature: \code void callback(int8_t temperature, void *user_data) \endcode 258 | * 259 | * This callback is triggered periodically with the period that is set by 260 | * {@link imu_v2_set_temperature_period}. The parameter is the temperature. 261 | */ 262 | #define IMU_V2_CALLBACK_TEMPERATURE 35 263 | 264 | /** 265 | * \ingroup BrickIMUV2 266 | * 267 | * Signature: \code void callback(int16_t x, int16_t y, int16_t z, void *user_data) \endcode 268 | * 269 | * This callback is triggered periodically with the period that is set by 270 | * {@link imu_v2_set_linear_acceleration_period}. The parameters are the 271 | * linear acceleration for the x, y and z axis. 272 | */ 273 | #define IMU_V2_CALLBACK_LINEAR_ACCELERATION 36 274 | 275 | /** 276 | * \ingroup BrickIMUV2 277 | * 278 | * Signature: \code void callback(int16_t x, int16_t y, int16_t z, void *user_data) \endcode 279 | * 280 | * This callback is triggered periodically with the period that is set by 281 | * {@link imu_v2_set_gravity_vector_period}. The parameters gravity vector 282 | * for the x, y and z axis. 283 | */ 284 | #define IMU_V2_CALLBACK_GRAVITY_VECTOR 37 285 | 286 | /** 287 | * \ingroup BrickIMUV2 288 | * 289 | * Signature: \code void callback(int16_t heading, int16_t roll, int16_t pitch, void *user_data) \endcode 290 | * 291 | * This callback is triggered periodically with the period that is set by 292 | * {@link imu_v2_set_orientation_period}. The parameters are the orientation 293 | * (heading (yaw), roll, pitch) of the IMU Brick in Euler angles. See 294 | * {@link imu_v2_get_orientation} for details. 295 | */ 296 | #define IMU_V2_CALLBACK_ORIENTATION 38 297 | 298 | /** 299 | * \ingroup BrickIMUV2 300 | * 301 | * Signature: \code void callback(int16_t w, int16_t x, int16_t y, int16_t z, void *user_data) \endcode 302 | * 303 | * This callback is triggered periodically with the period that is set by 304 | * {@link imu_v2_set_quaternion_period}. The parameters are the orientation 305 | * (x, y, z, w) of the IMU Brick in quaternions. See {@link imu_v2_get_quaternion} 306 | * for details. 307 | */ 308 | #define IMU_V2_CALLBACK_QUATERNION 39 309 | 310 | /** 311 | * \ingroup BrickIMUV2 312 | * 313 | * Signature: \code void callback(int16_t ret_acceleration[3], int16_t ret_magnetic_field[3], int16_t ret_angular_velocity[3], int16_t ret_euler_angle[3], int16_t ret_quaternion[4], int16_t ret_linear_acceleration[3], int16_t ret_gravity_vector[3], int8_t temperature, uint8_t calibration_status, void *user_data) \endcode 314 | * 315 | * This callback is triggered periodically with the period that is set by 316 | * {@link imu_v2_set_all_data_period}. The parameters are as for {@link imu_v2_get_all_data}. 317 | */ 318 | #define IMU_V2_CALLBACK_ALL_DATA 40 319 | 320 | 321 | /** 322 | * \ingroup BrickIMUV2 323 | * 324 | * This constant is used to identify a IMU Brick 2.0. 325 | * 326 | * The {@link imu_v2_get_identity} function and the 327 | * {@link IPCON_CALLBACK_ENUMERATE} callback of the IP Connection have a 328 | * \c device_identifier parameter to specify the Brick's or Bricklet's type. 329 | */ 330 | #define IMU_V2_DEVICE_IDENTIFIER 18 331 | 332 | /** 333 | * \ingroup BrickIMUV2 334 | * 335 | * This constant represents the display name of a IMU Brick 2.0. 336 | */ 337 | #define IMU_V2_DEVICE_DISPLAY_NAME "IMU Brick 2.0" 338 | 339 | /** 340 | * \ingroup BrickIMUV2 341 | * 342 | * Creates the device object \c imu_v2 with the unique device ID \c uid and adds 343 | * it to the IPConnection \c ipcon. 344 | */ 345 | void imu_v2_create(IMUV2 *imu_v2, const char *uid, IPConnection *ipcon); 346 | 347 | /** 348 | * \ingroup BrickIMUV2 349 | * 350 | * Removes the device object \c imu_v2 from its IPConnection and destroys it. 351 | * The device object cannot be used anymore afterwards. 352 | */ 353 | void imu_v2_destroy(IMUV2 *imu_v2); 354 | 355 | /** 356 | * \ingroup BrickIMUV2 357 | * 358 | * Returns the response expected flag for the function specified by the 359 | * \c function_id parameter. It is *true* if the function is expected to 360 | * send a response, *false* otherwise. 361 | * 362 | * For getter functions this is enabled by default and cannot be disabled, 363 | * because those functions will always send a response. For callback 364 | * configuration functions it is enabled by default too, but can be disabled 365 | * via the imu_v2_set_response_expected function. For setter functions it is 366 | * disabled by default and can be enabled. 367 | * 368 | * Enabling the response expected flag for a setter function allows to 369 | * detect timeouts and other error conditions calls of this setter as well. 370 | * The device will then send a response for this purpose. If this flag is 371 | * disabled for a setter function then no response is send and errors are 372 | * silently ignored, because they cannot be detected. 373 | */ 374 | int imu_v2_get_response_expected(IMUV2 *imu_v2, uint8_t function_id, bool *ret_response_expected); 375 | 376 | /** 377 | * \ingroup BrickIMUV2 378 | * 379 | * Changes the response expected flag of the function specified by the 380 | * \c function_id parameter. This flag can only be changed for setter 381 | * (default value: *false*) and callback configuration functions 382 | * (default value: *true*). For getter functions it is always enabled and 383 | * callbacks it is always disabled. 384 | * 385 | * Enabling the response expected flag for a setter function allows to detect 386 | * timeouts and other error conditions calls of this setter as well. The device 387 | * will then send a response for this purpose. If this flag is disabled for a 388 | * setter function then no response is send and errors are silently ignored, 389 | * because they cannot be detected. 390 | */ 391 | int imu_v2_set_response_expected(IMUV2 *imu_v2, uint8_t function_id, bool response_expected); 392 | 393 | /** 394 | * \ingroup BrickIMUV2 395 | * 396 | * Changes the response expected flag for all setter and callback configuration 397 | * functions of this device at once. 398 | */ 399 | int imu_v2_set_response_expected_all(IMUV2 *imu_v2, bool response_expected); 400 | 401 | /** 402 | * \ingroup BrickIMUV2 403 | * 404 | * Registers a callback with ID \c id to the function \c callback. The 405 | * \c user_data will be given as a parameter of the callback. 406 | */ 407 | void imu_v2_register_callback(IMUV2 *imu_v2, uint8_t id, void *callback, void *user_data); 408 | 409 | /** 410 | * \ingroup BrickIMUV2 411 | * 412 | * Returns the API version (major, minor, release) of the bindings for this 413 | * device. 414 | */ 415 | int imu_v2_get_api_version(IMUV2 *imu_v2, uint8_t ret_api_version[3]); 416 | 417 | /** 418 | * \ingroup BrickIMUV2 419 | * 420 | * Returns the calibrated acceleration from the accelerometer for the 421 | * x, y and z axis in 1/100 m/s². 422 | * 423 | * If you want to get the acceleration periodically, it is recommended 424 | * to use the callback {@link IMU_V2_CALLBACK_ACCELERATION} and set the period with 425 | * {@link imu_v2_set_acceleration_period}. 426 | */ 427 | int imu_v2_get_acceleration(IMUV2 *imu_v2, int16_t *ret_x, int16_t *ret_y, int16_t *ret_z); 428 | 429 | /** 430 | * \ingroup BrickIMUV2 431 | * 432 | * Returns the calibrated magnetic field from the magnetometer for the 433 | * x, y and z axis in 1/16 µT (Microtesla). 434 | * 435 | * If you want to get the magnetic field periodically, it is recommended 436 | * to use the callback {@link IMU_V2_CALLBACK_MAGNETIC_FIELD} and set the period with 437 | * {@link imu_v2_set_magnetic_field_period}. 438 | */ 439 | int imu_v2_get_magnetic_field(IMUV2 *imu_v2, int16_t *ret_x, int16_t *ret_y, int16_t *ret_z); 440 | 441 | /** 442 | * \ingroup BrickIMUV2 443 | * 444 | * Returns the calibrated angular velocity from the gyroscope for the 445 | * x, y and z axis in 1/16 °/s. 446 | * 447 | * If you want to get the angular velocity periodically, it is recommended 448 | * to use the callback {@link IMU_V2_CALLBACK_ANGULAR_VELOCITY} and set the period with 449 | * {@link imu_v2_set_angular_velocity_period}. 450 | */ 451 | int imu_v2_get_angular_velocity(IMUV2 *imu_v2, int16_t *ret_x, int16_t *ret_y, int16_t *ret_z); 452 | 453 | /** 454 | * \ingroup BrickIMUV2 455 | * 456 | * Returns the temperature of the IMU Brick. The temperature is given in 457 | * °C. The temperature is measured in the core of the BNO055 IC, it is not the 458 | * ambient temperature 459 | */ 460 | int imu_v2_get_temperature(IMUV2 *imu_v2, int8_t *ret_temperature); 461 | 462 | /** 463 | * \ingroup BrickIMUV2 464 | * 465 | * Returns the current orientation (heading, roll, pitch) of the IMU Brick as 466 | * independent Euler angles in 1/16 degree. Note that Euler angles always 467 | * experience a `gimbal lock `__. We 468 | * recommend that you use quaternions instead, if you need the absolute orientation. 469 | * 470 | * The rotation angle has the following ranges: 471 | * 472 | * * heading: 0° to 360° 473 | * * roll: -90° to +90° 474 | * * pitch: -180° to +180° 475 | * 476 | * If you want to get the orientation periodically, it is recommended 477 | * to use the callback {@link IMU_V2_CALLBACK_ORIENTATION} and set the period with 478 | * {@link imu_v2_set_orientation_period}. 479 | */ 480 | int imu_v2_get_orientation(IMUV2 *imu_v2, int16_t *ret_heading, int16_t *ret_roll, int16_t *ret_pitch); 481 | 482 | /** 483 | * \ingroup BrickIMUV2 484 | * 485 | * Returns the linear acceleration of the IMU Brick for the 486 | * x, y and z axis in 1/100 m/s². 487 | * 488 | * The linear acceleration is the acceleration in each of the three 489 | * axis of the IMU Brick with the influences of gravity removed. 490 | * 491 | * It is also possible to get the gravity vector with the influence of linear 492 | * acceleration removed, see {@link imu_v2_get_gravity_vector}. 493 | * 494 | * If you want to get the linear acceleration periodically, it is recommended 495 | * to use the callback {@link IMU_V2_CALLBACK_LINEAR_ACCELERATION} and set the period with 496 | * {@link imu_v2_set_linear_acceleration_period}. 497 | */ 498 | int imu_v2_get_linear_acceleration(IMUV2 *imu_v2, int16_t *ret_x, int16_t *ret_y, int16_t *ret_z); 499 | 500 | /** 501 | * \ingroup BrickIMUV2 502 | * 503 | * Returns the current gravity vector of the IMU Brick for the 504 | * x, y and z axis in 1/100 m/s². 505 | * 506 | * The gravity vector is the acceleration that occurs due to gravity. 507 | * Influences of additional linear acceleration are removed. 508 | * 509 | * It is also possible to get the linear acceleration with the influence 510 | * of gravity removed, see {@link imu_v2_get_linear_acceleration}. 511 | * 512 | * If you want to get the gravity vector periodically, it is recommended 513 | * to use the callback {@link IMU_V2_CALLBACK_GRAVITY_VECTOR} and set the period with 514 | * {@link imu_v2_set_gravity_vector_period}. 515 | */ 516 | int imu_v2_get_gravity_vector(IMUV2 *imu_v2, int16_t *ret_x, int16_t *ret_y, int16_t *ret_z); 517 | 518 | /** 519 | * \ingroup BrickIMUV2 520 | * 521 | * Returns the current orientation (w, x, y, z) of the IMU Brick as 522 | * `quaternions `__. 523 | * 524 | * You have to divide the returns values by 16383 (14 bit) to get 525 | * the usual range of -1.0 to +1.0 for quaternions. 526 | * 527 | * If you want to get the quaternions periodically, it is recommended 528 | * to use the callback {@link IMU_V2_CALLBACK_QUATERNION} and set the period with 529 | * {@link imu_v2_set_quaternion_period}. 530 | */ 531 | int imu_v2_get_quaternion(IMUV2 *imu_v2, int16_t *ret_w, int16_t *ret_x, int16_t *ret_y, int16_t *ret_z); 532 | 533 | /** 534 | * \ingroup BrickIMUV2 535 | * 536 | * Return all of the available data of the IMU Brick. 537 | * 538 | * * acceleration in 1/100 m/s² (see {@link imu_v2_get_acceleration}) 539 | * * magnetic field in 1/16 µT (see {@link imu_v2_get_magnetic_field}) 540 | * * angular velocity in 1/16 °/s (see {@link imu_v2_get_angular_velocity}) 541 | * * Euler angles in 1/16 ° (see {@link imu_v2_get_orientation}) 542 | * * quaternion 1/16383 (see {@link imu_v2_get_quaternion}) 543 | * * linear acceleration 1/100 m/s² (see {@link imu_v2_get_linear_acceleration}) 544 | * * gravity vector 1/100 m/s² (see {@link imu_v2_get_gravity_vector}) 545 | * * temperature in 1 °C (see {@link imu_v2_get_temperature}) 546 | * * calibration status (see below) 547 | * 548 | * The calibration status consists of four pairs of two bits. Each pair 549 | * of bits represents the status of the current calibration. 550 | * 551 | * * bit 0-1: Magnetometer 552 | * * bit 2-3: Accelerometer 553 | * * bit 4-5: Gyroscope 554 | * * bit 6-7: System 555 | * 556 | * A value of 0 means for "not calibrated" and a value of 3 means 557 | * "fully calibrated". In your program you should always be able to 558 | * ignore the calibration status, it is used by the calibration 559 | * window of the Brick Viewer and it can be ignored after the first 560 | * calibration. See the documentation in the calibration window for 561 | * more information regarding the calibration of the IMU Brick. 562 | * 563 | * If you want to get the data periodically, it is recommended 564 | * to use the callback {@link IMU_V2_CALLBACK_ALL_DATA} and set the period with 565 | * {@link imu_v2_set_all_data_period}. 566 | */ 567 | int imu_v2_get_all_data(IMUV2 *imu_v2, int16_t ret_acceleration[3], int16_t ret_magnetic_field[3], int16_t ret_angular_velocity[3], int16_t ret_euler_angle[3], int16_t ret_quaternion[4], int16_t ret_linear_acceleration[3], int16_t ret_gravity_vector[3], int8_t *ret_temperature, uint8_t *ret_calibration_status); 568 | 569 | /** 570 | * \ingroup BrickIMUV2 571 | * 572 | * Turns the orientation and direction LEDs of the IMU Brick on. 573 | */ 574 | int imu_v2_leds_on(IMUV2 *imu_v2); 575 | 576 | /** 577 | * \ingroup BrickIMUV2 578 | * 579 | * Turns the orientation and direction LEDs of the IMU Brick off. 580 | */ 581 | int imu_v2_leds_off(IMUV2 *imu_v2); 582 | 583 | /** 584 | * \ingroup BrickIMUV2 585 | * 586 | * Returns *true* if the orientation and direction LEDs of the IMU Brick 587 | * are on, *false* otherwise. 588 | */ 589 | int imu_v2_are_leds_on(IMUV2 *imu_v2, bool *ret_leds); 590 | 591 | /** 592 | * \ingroup BrickIMUV2 593 | * 594 | * A call of this function saves the current calibration to be used 595 | * as a starting point for the next restart of continuous calibration 596 | * of the IMU Brick. 597 | * 598 | * A return value of *true* means that the calibration could be used and 599 | * *false* means that it could not be used (this happens if the calibration 600 | * status is not "fully calibrated"). 601 | * 602 | * This function is used by the calibration window of the Brick Viewer, you 603 | * should not need to call it in your program. 604 | */ 605 | int imu_v2_save_calibration(IMUV2 *imu_v2, bool *ret_calibration_done); 606 | 607 | /** 608 | * \ingroup BrickIMUV2 609 | * 610 | * Sets the period in ms with which the {@link IMU_V2_CALLBACK_ACCELERATION} callback is triggered 611 | * periodically. A value of 0 turns the callback off. 612 | * 613 | * The default value is 0. 614 | */ 615 | int imu_v2_set_acceleration_period(IMUV2 *imu_v2, uint32_t period); 616 | 617 | /** 618 | * \ingroup BrickIMUV2 619 | * 620 | * Returns the period as set by {@link imu_v2_set_acceleration_period}. 621 | */ 622 | int imu_v2_get_acceleration_period(IMUV2 *imu_v2, uint32_t *ret_period); 623 | 624 | /** 625 | * \ingroup BrickIMUV2 626 | * 627 | * Sets the period in ms with which the {@link IMU_V2_CALLBACK_MAGNETIC_FIELD} callback is triggered 628 | * periodically. A value of 0 turns the callback off. 629 | */ 630 | int imu_v2_set_magnetic_field_period(IMUV2 *imu_v2, uint32_t period); 631 | 632 | /** 633 | * \ingroup BrickIMUV2 634 | * 635 | * Returns the period as set by {@link imu_v2_set_magnetic_field_period}. 636 | */ 637 | int imu_v2_get_magnetic_field_period(IMUV2 *imu_v2, uint32_t *ret_period); 638 | 639 | /** 640 | * \ingroup BrickIMUV2 641 | * 642 | * Sets the period in ms with which the {@link IMU_V2_CALLBACK_ANGULAR_VELOCITY} callback is triggered 643 | * periodically. A value of 0 turns the callback off. 644 | */ 645 | int imu_v2_set_angular_velocity_period(IMUV2 *imu_v2, uint32_t period); 646 | 647 | /** 648 | * \ingroup BrickIMUV2 649 | * 650 | * Returns the period as set by {@link imu_v2_set_angular_velocity_period}. 651 | */ 652 | int imu_v2_get_angular_velocity_period(IMUV2 *imu_v2, uint32_t *ret_period); 653 | 654 | /** 655 | * \ingroup BrickIMUV2 656 | * 657 | * Sets the period in ms with which the {@link IMU_V2_CALLBACK_TEMPERATURE} callback is triggered 658 | * periodically. A value of 0 turns the callback off. 659 | */ 660 | int imu_v2_set_temperature_period(IMUV2 *imu_v2, uint32_t period); 661 | 662 | /** 663 | * \ingroup BrickIMUV2 664 | * 665 | * Returns the period as set by {@link imu_v2_set_temperature_period}. 666 | */ 667 | int imu_v2_get_temperature_period(IMUV2 *imu_v2, uint32_t *ret_period); 668 | 669 | /** 670 | * \ingroup BrickIMUV2 671 | * 672 | * Sets the period in ms with which the {@link IMU_V2_CALLBACK_ORIENTATION} callback is triggered 673 | * periodically. A value of 0 turns the callback off. 674 | */ 675 | int imu_v2_set_orientation_period(IMUV2 *imu_v2, uint32_t period); 676 | 677 | /** 678 | * \ingroup BrickIMUV2 679 | * 680 | * Returns the period as set by {@link imu_v2_set_orientation_period}. 681 | */ 682 | int imu_v2_get_orientation_period(IMUV2 *imu_v2, uint32_t *ret_period); 683 | 684 | /** 685 | * \ingroup BrickIMUV2 686 | * 687 | * Sets the period in ms with which the {@link IMU_V2_CALLBACK_LINEAR_ACCELERATION} callback is triggered 688 | * periodically. A value of 0 turns the callback off. 689 | */ 690 | int imu_v2_set_linear_acceleration_period(IMUV2 *imu_v2, uint32_t period); 691 | 692 | /** 693 | * \ingroup BrickIMUV2 694 | * 695 | * Returns the period as set by {@link imu_v2_set_linear_acceleration_period}. 696 | */ 697 | int imu_v2_get_linear_acceleration_period(IMUV2 *imu_v2, uint32_t *ret_period); 698 | 699 | /** 700 | * \ingroup BrickIMUV2 701 | * 702 | * Sets the period in ms with which the {@link IMU_V2_CALLBACK_GRAVITY_VECTOR} callback is triggered 703 | * periodically. A value of 0 turns the callback off. 704 | */ 705 | int imu_v2_set_gravity_vector_period(IMUV2 *imu_v2, uint32_t period); 706 | 707 | /** 708 | * \ingroup BrickIMUV2 709 | * 710 | * Returns the period as set by {@link imu_v2_set_gravity_vector_period}. 711 | */ 712 | int imu_v2_get_gravity_vector_period(IMUV2 *imu_v2, uint32_t *ret_period); 713 | 714 | /** 715 | * \ingroup BrickIMUV2 716 | * 717 | * Sets the period in ms with which the {@link IMU_V2_CALLBACK_QUATERNION} callback is triggered 718 | * periodically. A value of 0 turns the callback off. 719 | */ 720 | int imu_v2_set_quaternion_period(IMUV2 *imu_v2, uint32_t period); 721 | 722 | /** 723 | * \ingroup BrickIMUV2 724 | * 725 | * Returns the period as set by {@link imu_v2_set_quaternion_period}. 726 | */ 727 | int imu_v2_get_quaternion_period(IMUV2 *imu_v2, uint32_t *ret_period); 728 | 729 | /** 730 | * \ingroup BrickIMUV2 731 | * 732 | * Sets the period in ms with which the {@link IMU_V2_CALLBACK_ALL_DATA} callback is triggered 733 | * periodically. A value of 0 turns the callback off. 734 | */ 735 | int imu_v2_set_all_data_period(IMUV2 *imu_v2, uint32_t period); 736 | 737 | /** 738 | * \ingroup BrickIMUV2 739 | * 740 | * Returns the period as set by {@link imu_v2_set_all_data_period}. 741 | */ 742 | int imu_v2_get_all_data_period(IMUV2 *imu_v2, uint32_t *ret_period); 743 | 744 | /** 745 | * \ingroup BrickIMUV2 746 | * 747 | * Enables the status LED. 748 | * 749 | * The status LED is the blue LED next to the USB connector. If enabled is is 750 | * on and it flickers if data is transfered. If disabled it is always off. 751 | * 752 | * The default state is enabled. 753 | */ 754 | int imu_v2_enable_status_led(IMUV2 *imu_v2); 755 | 756 | /** 757 | * \ingroup BrickIMUV2 758 | * 759 | * Disables the status LED. 760 | * 761 | * The status LED is the blue LED next to the USB connector. If enabled is is 762 | * on and it flickers if data is transfered. If disabled it is always off. 763 | * 764 | * The default state is enabled. 765 | */ 766 | int imu_v2_disable_status_led(IMUV2 *imu_v2); 767 | 768 | /** 769 | * \ingroup BrickIMUV2 770 | * 771 | * Returns *true* if the status LED is enabled, *false* otherwise. 772 | */ 773 | int imu_v2_is_status_led_enabled(IMUV2 *imu_v2, bool *ret_enabled); 774 | 775 | /** 776 | * \ingroup BrickIMUV2 777 | * 778 | * Returns the firmware and protocol version and the name of the Bricklet for a 779 | * given port. 780 | * 781 | * This functions sole purpose is to allow automatic flashing of v1.x.y Bricklet 782 | * plugins. 783 | */ 784 | int imu_v2_get_protocol1_bricklet_name(IMUV2 *imu_v2, char port, uint8_t *ret_protocol_version, uint8_t ret_firmware_version[3], char ret_name[40]); 785 | 786 | /** 787 | * \ingroup BrickIMUV2 788 | * 789 | * Returns the temperature in °C/10 as measured inside the microcontroller. The 790 | * value returned is not the ambient temperature! 791 | * 792 | * The temperature is only proportional to the real temperature and it has an 793 | * accuracy of +-15%. Practically it is only useful as an indicator for 794 | * temperature changes. 795 | */ 796 | int imu_v2_get_chip_temperature(IMUV2 *imu_v2, int16_t *ret_temperature); 797 | 798 | /** 799 | * \ingroup BrickIMUV2 800 | * 801 | * Calling this function will reset the Brick. Calling this function 802 | * on a Brick inside of a stack will reset the whole stack. 803 | * 804 | * After a reset you have to create new device objects, 805 | * calling functions on the existing ones will result in 806 | * undefined behavior! 807 | */ 808 | int imu_v2_reset(IMUV2 *imu_v2); 809 | 810 | /** 811 | * \ingroup BrickIMUV2 812 | * 813 | * Returns the UID, the UID where the Brick is connected to, 814 | * the position, the hardware and firmware version as well as the 815 | * device identifier. 816 | * 817 | * The position can be '0'-'8' (stack position). 818 | * 819 | * The device identifier numbers can be found :ref:`here `. 820 | * |device_identifier_constant| 821 | */ 822 | int imu_v2_get_identity(IMUV2 *imu_v2, char ret_uid[8], char ret_connected_uid[8], char *ret_position, uint8_t ret_hardware_version[3], uint8_t ret_firmware_version[3], uint16_t *ret_device_identifier); 823 | 824 | #ifdef __cplusplus 825 | } 826 | #endif 827 | 828 | #endif 829 | --------------------------------------------------------------------------------