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 {
00061 const char FLAG_R = {0x80};
00062
00063 const char ADDRESS_ACCLXYZ = {0x02};
00064 const char ADDRESS_VER = {0x00};
00065 const char ADDRESS_STATREG1 = {0x09};
00066 const char ADDRESS_STATREG2 = {0x0A};
00067 const char ADDRESS_STATREG3 = {0x0B};
00068 const char ADDRESS_STATREG4 = {0x0C};
00069 const char ADDRESS_CTRLREG0 = {0x0D};
00070 const char ADDRESS_CTRLREG1 = {0x0E};
00071 const char ADDRESS_CTRLREG2 = {0x0F};
00072 const char ADDRESS_SOFTRESET = {0x10};
00073 const char ADDRESS_EE_OFFSET_Z = {0x5A};
00074 const char ADDRESS_EE_OFFSET_Y = {0x59};
00075 const char ADDRESS_EE_OFFSET_X = {0x58};
00076 const char ADDRESS_EE_OFFSET_T = {0x57};
00077 const char ADDRESS_EE_OFFSET_LSB2 = {0x56};
00078 const char ADDRESS_EE_OFFSET_LSB1 = {0x55};
00079 const char ADDRESS_OFFSET_Z = {0x3A};
00080 const char ADDRESS_OFFSET_Y = {0x39};
00081 const char ADDRESS_OFFSET_X = {0x38};
00082 const char ADDRESS_OFFSET_T = {0x37};
00083 const char ADDRESS_OFFSET_LSB2 = {0x36};
00084 const char ADDRESS_OFFSET_LSB1 = {0x35};
00085 const char ADDRESS_EE_GAIN_Z = {0x54};
00086
00087 const char ADDRESS_BWTCS = {0x20};
00088 const char ADDRESS_RANGE = {0x35};
00089
00090 const double dFULLRANGELOOKUP[] = {1.0, 1.5, 2.0, 3.0, 4.0, 8.0, 16.0};
00091 const char COMMAND_FULLSCALE_G[] = {0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06};
00092
00093 const double dBWLOOKUP[] = {10, 20, 40, 75, 150, 300, 600, 1200};
00094 const char COMMAND_BANDWIDTH_HZ[] = {0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07};
00095
00096 const char COMMAND_SOFTRESET = {0xB6};
00097 const char COMMAND_SET_EEW = {0x01};
00098
00099 enum eSensorType {eACCEL, eTEMP, eBIAS_X, eBIAS_Y, eBIAS_Z};
00100
00101 const unsigned short MAX_NUM_SENSORS = 5;
00102
00103 const double dDEFAULT_MAXACC_g = 16.0;
00104 const std::string sSUB20SERIAL("0651");
00105 const double dDEFAULT_BANDWIDTH_Hz = 300;
00106 const double dDEFAULT_RATE_Hz = 500;
00107 const bool bDEFAULT_CALIBRATE = false;
00108 const double dCALIB_ACCURACY = 0.05;
00109
00110 const unsigned short uSERIALNUMLENGTH = 20;
00111
00112 const short iDEFAULT_CALIBCHIPSELECT= 0;
00113 }
00114
00115
00116 struct OneBma180Meas
00117 {
00118 bool bMeasAvailable;
00119 int iNumAccels;
00120 double dAccX[bma180_cmd::MAX_NUM_SENSORS];
00121 double dAccY[bma180_cmd::MAX_NUM_SENSORS];
00122 double dAccZ[bma180_cmd::MAX_NUM_SENSORS];
00123 double dTemp;
00124 ros::Time dtomeas;
00125 std::string serial_number;
00126 int chip_select[bma180_cmd::MAX_NUM_SENSORS];
00127 };
00128
00129
00131
00137 class Bma180
00138 {
00139 public:
00141
00153 Bma180( double max_acceleration_g, double dBandwidth_Hz, bool bCalibrate, double dRate_Hz, std::string sSub20Serial );
00154
00156
00160 ~Bma180();
00161
00163
00173 void GetMeasurements( std::list<OneBma180Meas>& );
00174
00175 private:
00176
00177
00178 struct OneBma180Config
00179 {
00180 double dFullScaleRange;
00181 double dSensorBandwidth;
00182 bool bConfigured;
00183 unsigned short uiBiasImageX;
00184 unsigned short uiBiasImageY;
00185 unsigned short uiBiasImageZ;
00186 double iNumOfCalibMeas;
00187 };
00188
00189
00190 struct OneSub20Config
00191 {
00192 std::string strSub20Serial;
00193 sub_handle handle_subdev;
00194 sub_device subdev;
00195 bool bSubSPIConfigured;
00196 OneBma180Config Bma180Cluster[bma180_cmd::MAX_NUM_SENSORS];
00197 };
00198 std::list<OneSub20Config> Sub20Device_list;
00199
00200
00201 bool bExecuteCalibration;
00202 bool bCalibrationCompleted;
00203 bma180_calibrate calib_bma180;
00204
00205
00206 char chMaxAccRange_selected;
00207 char chBW_selected;
00208 int iCalib_CS;
00209
00210
00211 sub_handle subhndl;
00212 bool bSubDeviceOpen;
00213 bool bSubDeviceConfigured;
00214 std::string serial_number;
00215
00217 double bma180data_to_double( char, char, bma180_cmd::eSensorType, int *, double );
00218
00220 unsigned short bma180data_to_uint( char, char, bma180_cmd::eSensorType );
00221
00223 bool read_biassettings( sub_handle, int, unsigned short*, unsigned short*, unsigned short* );
00224
00226 bool set_biassettings( sub_handle, int, unsigned short, unsigned short, unsigned short, bool );
00227
00229 bool read_byte_eeprom_sub20( char, char*, unsigned short, sub_handle );
00230
00232 bool write_bit_eeprom_sub20( char, unsigned short, unsigned short, char, unsigned short, sub_handle );
00233
00235 void confsens_on_sub20( OneSub20Config*, char, char );
00236
00238 void set_calibstatus( bool bCalibrate );
00239 };
00240
00241 #endif
00242