00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049 #ifndef BMA180_H_
00050 #define BMA180_H_
00051
00052 #include "bma180/bma180meas.h"
00053 #include "bma180/bma180err.h"
00054 #include "bma180/bma180_calibrate.h"
00055 #include <list>
00056 #include <libsub.h>
00057
00058
00059 namespace bma180_cmd {
00060 const char chFLAG_R = {0x80};
00061
00062 const char chADR_ACCLXYZ = {0x02};
00063 const char chADR_VER = {0x00};
00064 const char chADR_STATREG1 = {0x09};
00065 const char chADR_STATREG2 = {0x0A};
00066 const char chADR_STATREG3 = {0x0B};
00067 const char chADR_STATREG4 = {0x0C};
00068 const char chADR_CTRLREG0 = {0x0D};
00069 const char chADR_CTRLREG1 = {0x0E};
00070 const char chADR_CTRLREG2 = {0x0F};
00071 const char chADR_SOFTRESET = {0x10};
00072 const char chADR_EE_OFFSET_Z = {0x5A};
00073 const char chADR_EE_OFFSET_Y = {0x59};
00074 const char chADR_EE_OFFSET_X = {0x58};
00075 const char chADR_EE_OFFSET_T = {0x57};
00076 const char chADR_EE_OFFSET_LSB2 = {0x56};
00077 const char chADR_EE_OFFSET_LSB1 = {0x55};
00078 const char chADR_OFFSET_Z = {0x3A};
00079 const char chADR_OFFSET_Y = {0x39};
00080 const char chADR_OFFSET_X = {0x38};
00081 const char chADR_OFFSET_T = {0x37};
00082 const char chADR_OFFSET_LSB2 = {0x36};
00083 const char chADR_OFFSET_LSB1 = {0x35};
00084 const char chADR_EE_GAIN_Z = {0x54};
00085
00086 const char chADR_BWTCS = {0x20};
00087 const char chADR_RANGE = {0x35};
00088
00089 const double dFULLRANGELOOKUP[] = {1.0, 1.5, 2.0, 3.0, 4.0, 8.0, 16.0};
00090 const char chCMD_FULLSCALE_G[]= {0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06};
00091
00092 const double dBWLOOKUP[] = {10, 20, 40, 75, 150, 300, 600, 1200};
00093 const char chCMD_BANDWIDTH_HZ[]= {0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07};
00094
00095 const char chCMD_SOFTRESET = {0xB6};
00096 const char chCMD_SET_EEW = {0x01};
00097
00098 enum eSensorType {eACCEL, eTEMP, eBIAS_X, eBIAS_Y, eBIAS_Z};
00099
00100 const unsigned short iMAXNUM_OF_SENSORS = 5;
00101
00102 const double dDEFAULT_MAXACC_g = 16;
00103 const std::string sSUB20SERIAL("0651");
00104 const double dDEFAULT_BANDWIDTH_Hz = 300;
00105 const double dDEFAULT_RATE_Hz = 500;
00106 const bool bDEFAULT_CALIBRATE = false;
00107 const double dCALIB_ACCURACY = 0.05;
00108
00109 const unsigned short uSERIALNUMLENGTH = 20;
00110
00111 const short iDEFAULT_CALIBCHIPSELECT= 0;
00112 }
00113
00114
00115 struct OneBma180Meas {
00116 bool bMeasAvailable;
00117 int iNumAccels;
00118 double dAccX[bma180_cmd::iMAXNUM_OF_SENSORS];
00119 double dAccY[bma180_cmd::iMAXNUM_OF_SENSORS];
00120 double dAccZ[bma180_cmd::iMAXNUM_OF_SENSORS];
00121 double dTemp;
00122 ros::Time dtomeas;
00123 std::string strSerial;
00124 int iChipSelect[bma180_cmd::iMAXNUM_OF_SENSORS];
00125 };
00126
00127
00129
00135 class Bma180 {
00136 public:
00138
00150 Bma180(double, double, bool, double, std::string);
00151
00153
00157 ~Bma180();
00158
00160
00170 void GetMeasurements( std::list<OneBma180Meas>& );
00171
00172 private:
00173
00174 struct OneBma180Config {
00175 double dFullScaleRange;
00176 double dSensorBandwidth;
00177 bool bConfigured;
00178 unsigned short uiBiasImageX;
00179 unsigned short uiBiasImageY;
00180 unsigned short uiBiasImageZ;
00181 double iNumOfCalibMeas;
00182 };
00183
00184 struct OneSub20Config {
00185 std::string strSub20Serial;
00186 sub_handle handle_subdev;
00187 sub_device subdev;
00188 bool bSubSPIConfigured;
00189 OneBma180Config Bma180Cluster[bma180_cmd::iMAXNUM_OF_SENSORS];
00190 };
00191 std::list<OneSub20Config> Sub20Device_list;
00192
00193
00194 bool bExecuteCalibration;
00195 bool bCalibrationCompleted;
00196 bma180_calibrate calib_bma180;
00197
00198
00199 char chMaxAccRange_selected;
00200 char chBW_selected;
00201 int iCalib_CS;
00202
00203
00204 sub_handle subhndl;
00205 bool bSubDeviceOpen;
00206 bool bSubDeviceConfigured;
00207 std::string strSerial;
00208
00210 double bma180data_to_double(char, char, bma180_cmd::eSensorType, int *, double);
00211
00213 unsigned short bma180data_to_uint(char, char, bma180_cmd::eSensorType );
00214
00216 bool read_biassettings(sub_handle, int, unsigned short*, unsigned short*, unsigned short*);
00217
00219 bool set_biassettings(sub_handle, int, unsigned short, unsigned short, unsigned short, bool);
00220
00222 bool read_byte_eeprom_sub20(char, char*, unsigned short, sub_handle);
00223
00225 bool write_bit_eeprom_sub20(char, unsigned short, unsigned short, char, unsigned short, sub_handle);
00226
00228 void confsens_on_sub20(OneSub20Config*, char, char);
00229
00231 void set_calibstatus(bool bCalibrate);
00232 };
00233
00234 #endif
00235