Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed ros_lib_kinetic
definitions.h
00001 #ifndef __DEFINITIONS_H__ 00002 #define __DEFINITIONS_H__ 00003 00004 #include "mbed.h" 00005 #include <BNO055.h> 00006 #include <Mx28.h> 00007 00008 // Generic definitions 00009 #define TRUE 1 00010 #define FALSE 0 00011 00012 // ROS definitions 00013 #define ROSROLL 0 00014 #define ROSPITCH 1 00015 #define ROSYAW 2 00016 #define ROSHEIGHT 3 00017 #define ROSMODE 4 00018 #define ROSYAWSP 5 00019 #define ROSROLLSP 6 00020 #define ROSPITCHSP 7 00021 #define ROSHEIGHTSP 8 00022 #define ROSDATALENGTH 9 00023 00024 // Gimbal definitions 00025 #define YAWID 1 00026 #define PITCHID 2 00027 #define ROLLID 3 00028 #define YAWZERO 2015 00029 #define PITCHZERO 2350 00030 #define ROLLZERO 2302 00031 #define YAWMIN 0 // -177 degrees. 00032 #define YAWMAX 4063 // +177 degrees. 00033 #define PITCHMIN 1326 // -90 degrees. 00034 #define PITCHMAX 3000 // +90 degrees is at 3374 00035 #define ROLLMIN 2100 // -90 degrees is at 1278 00036 #define ROLLMAX 2500 // +90 degrees is at 3374 00037 #define SERVOSPEEDMIN 1 // Min speed for gimbal servos 00038 #define SERVOSPEEDMAX 200 // Max speed for gimbal servos 00039 #define DYNASCALE 11 // Should be 11.4, but int is currently being used 00040 00041 // Lift definitions 00042 #define LIFTUP 1 00043 #define LIFTDOWN 0 00044 #define LIFTHEIGHTMAX 3000 // 119.6 cm should be 3000 00045 #define LIFTHEIGHTMIN 5 //51.6 cm 00046 // Delta Height for Lift is 68cm 00047 00048 // Classes 00049 struct fields{ 00050 volatile int yaw; 00051 int yawSpeed; 00052 volatile int pitch; 00053 int pitchSpeed; 00054 volatile int roll; 00055 int rollSpeed; 00056 volatile int height; 00057 volatile int heightSpeed; 00058 bool stabilize; 00059 bool masterOn; 00060 bool liftRun; 00061 bool gimbalRun; 00062 bool shutdown; 00063 bool initialize; 00064 volatile int mode; 00065 }; 00066 00067 extern struct fields control; 00068 extern struct fields rosInput; 00069 extern volatile int currentPosition; 00070 extern float liftDutyCycle; 00071 extern int prevPosition; 00072 extern bool stall; 00073 extern bool rosFlag; 00074 extern bool eStopFlag; 00075 extern int stallcount; 00076 extern const int addr; 00077 extern Ticker hallInt; 00078 extern Timer filter_hall1; 00079 extern Timer rosMode_Delay; 00080 extern PwmOut liftSpeed; 00081 extern DigitalOut liftDirection; 00082 extern DynamixelClass gimbal; 00083 extern DigitalOut value0; 00084 extern DigitalOut value1; 00085 extern InterruptIn eStop; 00086 00087 #endif
Generated on Tue Jul 12 2022 19:42:54 by
