$search
00001 /* 00002 * Copyright (c) 2011, Robert Bosch LLC 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of Robert Bosch LLC nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 /* 00031 * bma180.cpp 00032 * 00033 * Created on: Jul 26, 2011 00034 * Author: Lucas Marti, Robert Bosch LLC 00035 * Editor: Nikhil Deshpande, Philip Roan 00036 */ 00037 00038 // Standard headers 00039 #include <iostream> 00040 #include <string> 00041 #include <sstream> 00042 #include <math.h> 00043 #include <vector> 00044 // ROS headers 00045 #include <ros/ros.h> 00046 #include <ros/time.h> 00047 // ROS messages 00048 #include "bma180/bma180.h" 00049 00050 00051 Bma180::Bma180( double dMaxAcc_g, double dBandwidth_Hz, bool bCalibrate, double dRate_Hz, std::string sSub20Serial ): 00052 bSubDeviceOpen (false), 00053 bSubDeviceConfigured (false) 00054 { 00055 int iSpiErr; // Error code for std Sub20 API 00056 int iSPI_cfg_set; // Set SPI config 00057 int iSPI_cfg_get; // Get SPI config 00058 int iADCErr; // Error code for std Sub20 API 00059 int iADC_cfg_set; // Set ADC config 00060 int iNumOfRanges; 00061 int iElCount; 00062 std::stringstream ss_errmsg; 00063 std::string ss_config, sub20Serial; 00064 sub_device sub20dev; 00065 sub_handle sub20handle; 00066 OneSub20Config OneSub20Configuration; 00067 00068 ROS_INFO("--------------------------------------"); 00069 ROS_INFO("Max acceleration entered:: %f ", dMaxAcc_g); 00070 ROS_INFO("Sensor bandwidth entered:: %f ", dBandwidth_Hz); 00071 ROS_INFO("Sensor Reading Rate entered:: %f ", dRate_Hz); 00072 ROS_INFO("--------------------------------------"); 00073 00074 //Retrieve calibration data from user 00075 set_calibstatus( bCalibrate ); 00076 00077 // Evaluate the accelerometer range to be selected 00078 iNumOfRanges = sizeof(bma180_cmd::chCMD_FULLSCALE_G) / sizeof(char); 00079 iElCount = 0; 00080 while( (dMaxAcc_g > bma180_cmd::dFULLRANGELOOKUP[iElCount]) && (iElCount < iNumOfRanges) ) 00081 { 00082 iElCount++; 00083 }; 00084 ROS_INFO("Range chosen G:: %f ", bma180_cmd::dFULLRANGELOOKUP[iElCount]); 00085 00086 chMaxAccRange_selected = bma180_cmd::chCMD_FULLSCALE_G[iElCount]; 00087 00088 // Evaluate the bandwidth to be selected 00089 iNumOfRanges = sizeof(bma180_cmd::chCMD_BANDWIDTH_HZ) / sizeof(char); 00090 iElCount = 0; 00091 while( (dBandwidth_Hz > bma180_cmd::dBWLOOKUP[iElCount]) && (iElCount < iNumOfRanges) ) 00092 { 00093 iElCount++; 00094 }; 00095 ROS_INFO("Range chosen BW:: %f ", bma180_cmd::dBWLOOKUP[iElCount]); 00096 00097 chBW_selected = bma180_cmd::chCMD_BANDWIDTH_HZ[iElCount]; 00098 00099 // Open connected Sub20 Devices 00100 sub20dev = 0; 00101 sub20dev = sub_find_devices( sub20dev ); 00102 while( sub20dev != 0 ) 00103 { 00104 sub20handle = sub_open( sub20dev ); 00105 // on success, sub_open returns non-zero handle 00106 if( sub20handle > 0 ) 00107 { 00108 sub20Serial.clear(); 00109 sub20Serial.resize( bma180_cmd::uSERIALNUMLENGTH ); 00110 sub_get_serial_number( sub20handle, const_cast<char*>(sub20Serial.c_str()), sub20Serial.size() ); 00111 std::cout << "Serial Number : " << sub20Serial << std::endl; 00112 if( strcmp(sub20Serial.c_str(), sSub20Serial.c_str()) == 0 ) 00113 { 00114 subhndl = sub20handle; 00115 00116 // Configure Sub20 device 00117 std::cout << "---Initializing SPI Interface---" << " \n"; 00118 // Read current SPI configuration 00119 iSpiErr = sub_spi_config( sub20handle, 0, &iSPI_cfg_get ); 00120 std::cout << "Sub SPI config : " << iSPI_cfg_get << " \n"; 00121 //Important: The SPI interface does not work properly at higher frequencies, i.e. > 2MHz 00122 // SET: Polarity Fall, SetupSmpl, MSB first, 2MHZ 00123 iSPI_cfg_set = SPI_ENABLE|SPI_CPOL_FALL|SPI_SETUP_SMPL|SPI_MSB_FIRST|SPI_CLK_2MHZ; 00124 //Configure SPI 00125 iSpiErr = sub_spi_config( sub20handle, iSPI_cfg_set, 0 ); 00126 //Read current SPI configuration 00127 iSpiErr = sub_spi_config( sub20handle, 0, &iSPI_cfg_get ); 00128 //verify if sub20 device has accepted the configuration 00129 if( iSPI_cfg_get == iSPI_cfg_set ) 00130 { 00131 std::cout<< "SPI Configuration : " << iSPI_cfg_set << " successfully stored \n"; 00132 //Subdevice has been configured successfully 00133 OneSub20Configuration.bSubSPIConfigured = true; 00134 OneSub20Configuration.handle_subdev = sub20handle; 00135 00136 // Configure Sensors on Sub20 00137 confsens_on_sub20( &OneSub20Configuration, chMaxAccRange_selected, chBW_selected ); 00138 } 00139 else 00140 { 00141 ROS_INFO("ERROR - SPI Configuration : %d not accepted by device", iSPI_cfg_set); 00142 //Subdevice could not be configured 00143 OneSub20Configuration.bSubSPIConfigured = false; 00144 } 00145 if( OneSub20Configuration.bSubSPIConfigured ) 00146 { 00147 //string needs to be cleared otherwise conversion is going wrong 00148 strSerial.clear(); 00149 strSerial.resize( bma180_cmd::uSERIALNUMLENGTH ); 00150 sub_get_serial_number( sub20handle, const_cast<char*>(strSerial.c_str()), strSerial.size() ); 00151 OneSub20Configuration.strSub20Serial = strSerial; 00152 OneSub20Configuration.subdev = sub20dev; 00153 std::cout << "Device Handle : " << OneSub20Configuration.handle_subdev << std::endl; 00154 std::cout << "Serial Number : " << OneSub20Configuration.strSub20Serial << std::endl; 00155 00156 // Push element onto list of subdevices 00157 Sub20Device_list.push_back( OneSub20Configuration ); 00158 std::cout << "... Publishing to topic /bma180 ... " << std::endl; 00159 } 00160 break; 00161 } 00162 else 00163 { 00164 sub_close( sub20handle ); 00165 } 00166 } 00167 //find next device, sub_find_devices using current provides next 00168 sub20dev = sub_find_devices( sub20dev ); 00169 } 00170 }; 00171 00172 Bma180::~Bma180() 00173 { 00174 int iSpiErr; 00175 OneSub20Config OneSub20Configuration; 00176 //close opened subdevices 00177 // Disable SPI 00178 iSpiErr = sub_spi_config( subhndl, 0, 0 ); 00179 // Close USB device 00180 sub_close( subhndl ); 00181 while( !Sub20Device_list.empty() ) 00182 { 00183 OneSub20Configuration = Sub20Device_list.back(); 00184 std::cout << "Sub device removed " << OneSub20Configuration.strSub20Serial << "\n"; 00185 Sub20Device_list.pop_back(); 00186 } 00187 }; 00188 00189 void Bma180::GetMeasurements( std::list<OneBma180Meas> &list_meas ) 00190 { 00191 char chACC_XYZ[7]; //Containing 00192 double dAccX, dAccY, dAccZ; 00193 double dEstBiasX, dEstBiasY, dEstBiasZ; 00194 int uiBcorrX, uiBcorrY, uiBcorrZ, uiRawX, uiRawY, uiRawZ; 00195 double dTemp; 00196 int iSpiErr, iADCErr, dummy, j = 0; 00197 bool SPIMeas = false, ADCMeas = false; 00198 OneBma180Meas sMeas; 00199 ros::Time dtomeas; 00200 char chCMD; 00201 std::stringstream ss_errmsg; 00202 std::list<OneSub20Config>::iterator iterat; 00203 int iChipSelect; 00204 00205 //verify that a subdevice is connected 00206 if( 1 > (int)Sub20Device_list.size() ) 00207 { 00208 throw std::string ("No SubDevice connected OR access rights to USB not given"); 00209 } 00210 00211 //Trace sub20 list 00212 for( iterat = Sub20Device_list.begin(); iterat != Sub20Device_list.end(); iterat++ ) 00213 { 00214 //verify if the sub20 device is configured (which should be the case as only configured sub20ies are pushed on list) 00215 if( iterat->bSubSPIConfigured == true ) 00216 { 00217 //Trace through cluster 00218 for( iChipSelect = 0; iChipSelect < bma180_cmd::iMAXNUM_OF_SENSORS; iChipSelect++ ) 00219 { 00220 //verify if sensor is available on respective chipselect 00221 if( iterat->Bma180Cluster[iChipSelect].bConfigured == true ) 00222 { 00223 iSpiErr = 0; 00224 //NOTE: Not executed in order to save one SPI transfer 00225 // //ensure CS is high 00226 // //iSpiErr = sub_spi_transfer( iterat->handle_subdev, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00227 // //send read command 00228 chCMD = bma180_cmd::chADR_ACCLXYZ | bma180_cmd::chFLAG_R; 00229 iSpiErr += sub_spi_transfer( iterat->handle_subdev, &chCMD, 0, 1, SS_CONF(iChipSelect,SS_L) ); 00230 iSpiErr += sub_spi_transfer( iterat->handle_subdev, 0, chACC_XYZ, 7, SS_CONF(iChipSelect,SS_L) ); 00231 //ensure CS is high 00232 iSpiErr += sub_spi_transfer( iterat->handle_subdev, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00233 00234 if( iSpiErr == 0 ) 00235 { 00236 SPIMeas = true; 00237 dAccX = bma180data_to_double(chACC_XYZ[1], chACC_XYZ[0], bma180_cmd::eACCEL, &uiRawX, iterat->Bma180Cluster[iChipSelect].dFullScaleRange ); 00238 dAccY = bma180data_to_double(chACC_XYZ[3], chACC_XYZ[2], bma180_cmd::eACCEL, &uiRawY, iterat->Bma180Cluster[iChipSelect].dFullScaleRange ); 00239 dAccZ = bma180data_to_double(chACC_XYZ[5], chACC_XYZ[4], bma180_cmd::eACCEL, &uiRawZ, iterat->Bma180Cluster[iChipSelect].dFullScaleRange ); 00240 dTemp = bma180data_to_double(chACC_XYZ[6], chACC_XYZ[6], bma180_cmd::eTEMP, &dummy, iterat->Bma180Cluster[iChipSelect].dFullScaleRange ); 00241 00242 // Collect data for all chipSelects 00243 sMeas.dAccX[j] = dAccX; 00244 sMeas.dAccY[j] = dAccY; 00245 sMeas.dAccZ[j] = dAccZ; 00246 sMeas.dTemp = dTemp; 00247 sMeas.iChipSelect[j] = iChipSelect; 00248 j++; 00249 sMeas.iNumAccels = j; 00250 00251 // Execute calibration if desired 00252 // Note: For calibration procedure, only one XDIMAX box is allowed to be connected 00253 if( (bExecuteCalibration == true) && (2>(int)Sub20Device_list.size()) ) 00254 { 00255 if( iChipSelect == iCalib_CS ) 00256 { 00257 if( (calib_bma180.calibsens_completed() == false) && (calib_bma180.calibsens_set() == false) ) 00258 { 00259 std::cout << " Bias read from image : " << iterat->Bma180Cluster[iChipSelect].uiBiasImageX << " " << iterat->Bma180Cluster[iChipSelect].uiBiasImageY << " " << iterat->Bma180Cluster[iChipSelect].uiBiasImageZ << std::endl; 00260 //set the sensor to be calibrated 00261 calib_bma180.setcalibsens( sMeas ); 00262 } 00263 else 00264 { 00265 calib_bma180.setdata_bma180(sMeas); 00266 } 00267 if( (calib_bma180.calibsens_completed())&&(!calib_bma180.verification_active()) ) 00268 { 00269 // Get estimated sensor biases 00270 calib_bma180.get_estbiases( &dEstBiasX, &dEstBiasY, &dEstBiasZ ); 00271 std::cout << "estimated biases : " << dEstBiasX << " " << dEstBiasY << " " << dEstBiasZ << std::endl; 00272 00273 // calculate adjustment 00274 // +0.5 for typecast to get propper rounding 00275 // 2048: Bias has 12 bit, thus halfrange is 2^11 where as bias corr scales by range 00276 int iBcorrX, iBcorrY, iBcorrZ; 00277 iBcorrX = ((short)(dEstBiasX/iterat->Bma180Cluster[iChipSelect].dFullScaleRange*2048+0.5)); 00278 iBcorrY = ((short)(dEstBiasY/iterat->Bma180Cluster[iChipSelect].dFullScaleRange*2048+0.5)) ; 00279 iBcorrZ = ((short)((dEstBiasZ-1)/iterat->Bma180Cluster[iChipSelect].dFullScaleRange*2048+0.5)) ; 00280 std::cout << "Bias adjustments [X Y Z] " << iBcorrX << " " << iBcorrY << " " << iBcorrZ << std::endl; 00281 std::cout << "Image values before adjustments " << iterat->Bma180Cluster[iChipSelect].uiBiasImageX << " " << iterat->Bma180Cluster[iChipSelect].uiBiasImageY << " " << iterat->Bma180Cluster[iChipSelect].uiBiasImageZ << std::endl; 00282 uiBcorrX = (unsigned short) (iterat->Bma180Cluster[iChipSelect].uiBiasImageX - ((short)(dEstBiasX/bma180_cmd::dFULLRANGELOOKUP[6]*2048)) ); 00283 uiBcorrY = (unsigned short) (iterat->Bma180Cluster[iChipSelect].uiBiasImageY - ((short)(dEstBiasY/bma180_cmd::dFULLRANGELOOKUP[6]*2048)) ); 00284 uiBcorrZ = (unsigned short) (iterat->Bma180Cluster[iChipSelect].uiBiasImageZ - ((short)((dEstBiasZ-1)/bma180_cmd::dFULLRANGELOOKUP[6]*2048))); 00285 00286 std::cout << "corrected biases " << uiBcorrX << " " << uiBcorrY << " " << uiBcorrZ << std::endl; 00287 00288 // Write to image 00289 if( !set_biassettings(iterat->handle_subdev, iChipSelect, uiBcorrX, uiBcorrY, uiBcorrZ, false) ) 00290 { 00291 bExecuteCalibration = false; 00292 throw std::string("Bias corrections cannot be written to image - Calibration procedure aborted"); 00293 } 00294 00295 // Activate verification 00296 if( !calib_bma180.biasverify() ) 00297 { 00298 bExecuteCalibration = false; 00299 throw std::string("BiasVerification cannot be executed - Calibration procedure aborted"); 00300 } 00301 } 00302 00303 if( (calib_bma180.calibsens_completed()) && (calib_bma180.verification_active()) && (calib_bma180.verification_completed()) ) 00304 { 00305 std::cout << "-----------------------------------------" << std::endl; 00306 std::cout << "...............VERIFY BIASES............." << std::endl; 00307 std::cout << "-----------------------------------------" << std::endl; 00308 00309 // Get verified biases after image write 00310 if( !calib_bma180.get_verifiedbiases(&dEstBiasX, &dEstBiasY, &dEstBiasZ) ) 00311 { 00312 bExecuteCalibration = false; 00313 throw std::string("Verified biases cannot be retrieved - Calibration procedure aborted"); 00314 }; 00315 00316 if( (bma180_cmd::dCALIB_ACCURACY > fabs(dEstBiasX)) && (bma180_cmd::dCALIB_ACCURACY > fabs(dEstBiasY)) && (bma180_cmd::dCALIB_ACCURACY > fabs(dEstBiasZ-1)) ) 00317 { 00318 // Writing EEPROM 00319 uiBcorrX = 0; 00320 uiBcorrY = 0; 00321 uiBcorrZ = 0; 00322 std::string myAnswer; 00323 std::cin.ignore(); 00324 std::cout << "Really write EEPROM <Y/N>? "; 00325 std::getline( std::cin, myAnswer ); 00326 if( (0 == myAnswer.find('Y')) || (0 == myAnswer.find('y')) ) 00327 { 00328 if( !set_biassettings(iterat->handle_subdev, iChipSelect, uiBcorrX, uiBcorrY, uiBcorrZ, true) ) 00329 { 00330 bExecuteCalibration = false; 00331 throw std::string("Biases cannot be written into EEPROM - Calibration procedure aborted"); 00332 }; 00333 ROS_INFO("++++++EEPROM HAS BEEN WRITTEN+++++++"); 00334 00335 } 00336 else 00337 { 00338 ROS_INFO("++++++EEPROM WRITE ABORTED++++++"); 00339 } 00340 } 00341 else 00342 { 00343 std::cout << "Error values " << fabs(dEstBiasX) << " " << fabs(dEstBiasY) << " " << fabs(dEstBiasZ-1) << std::endl; 00344 bExecuteCalibration = false; 00345 throw std::string("Bias verification failed, calib values too large - Calibration procedure aborted"); 00346 } 00347 //We are done with calibration 00348 bExecuteCalibration = false; 00349 std::cout << "calibration completed hehe" << std::endl; 00350 } 00351 } 00352 } 00353 else 00354 { 00355 if( (bExecuteCalibration == true) && (1<(int)Sub20Device_list.size()) ) 00356 { 00357 throw std::string("As a pre-caution: For calibration, only ONE SubDevice must be connected"); 00358 } 00359 } 00360 } 00361 else 00362 { 00363 throw std::string("Error on SPI communication - keep on running though"); 00364 } 00365 } //config verify 00366 } //scanning through all the chipselects 00367 } 00368 // Only publish data after all data for all chipSelects is collected 00369 if( SPIMeas ) 00370 { 00371 sMeas.dtomeas = ros::Time::now(); 00372 sMeas.bMeasAvailable = true; 00373 sMeas.strSerial = iterat->strSub20Serial; 00374 //Push measurement onto heap 00375 list_meas.push_back( sMeas ); 00376 } 00377 else 00378 { 00379 throw std::string("SUB20 connected but not configured - Restart of node suggested"); 00380 } 00381 } //sub20 for loop 00382 }; 00383 00384 double Bma180::bma180data_to_double( char chMSB, char chLSB, bma180_cmd::eSensorType eSensor, int *raw, double dAccScale ) 00385 { 00386 short s16int; // 2 byte int to build message 00387 double dSensorMeas; // Scaled sensor measurement 00388 00389 switch( eSensor ) 00390 { 00391 // Retrieve Accel Data 00392 case bma180_cmd::eACCEL: 00393 //verify if pos or neg 00394 if( (chMSB & 0x80) == 0 ) 00395 { 00396 //positive number 00397 s16int = (short) ((((unsigned short)chMSB)&0xFF)<<6)+((((unsigned short)chLSB)&0xFC)>>2); 00398 } 00399 else 00400 { 00401 //negative number 00402 //set MSB (sign) to zero and build 2 complement unsigned; offset 8192 for 2^13 00403 s16int = (short) (((((unsigned short)chMSB)&0x7F)<<6)+((((unsigned short)chLSB)&0xFC)>>2) - 8192); 00404 } 00405 dSensorMeas = (( (double) s16int) / 8192)*dAccScale; 00406 break; 00407 00408 // Convert Temperature Data 00409 case bma180_cmd::eTEMP: 00410 //verify if pos or neg 00411 if( (chLSB & 0x80) == 0 ) 00412 { 00413 //positive number 00414 s16int = (short) (((unsigned short)chLSB)&0xFF); 00415 } 00416 else 00417 { 00418 //negative number 00419 //set MSB (sign) to zero and build 2 complement unsigned; offset 128 for 2^7 00420 s16int = (short) ((((unsigned short)chLSB)&0x7F) - 128 ); 00421 }; 00422 dSensorMeas = (( (double) s16int) / 8192)*2; 00423 break; 00424 00425 default : 00426 dSensorMeas = 0; 00427 } 00428 *raw = s16int; 00429 return dSensorMeas; 00430 }; 00431 00432 unsigned short Bma180::bma180data_to_uint( char chMSB, char chLSB, bma180_cmd::eSensorType eSensor ) 00433 { 00434 unsigned short u16int_bias; //2 byte int to build message 00435 00436 switch (eSensor) 00437 { 00438 // Bias X axis data 00439 case bma180_cmd::eBIAS_X: 00440 u16int_bias = (short) ((((unsigned short)chMSB)&0xFF)<<4)+((((unsigned short)chLSB)&0xF0)>>4); 00441 break; 00442 // Bias Y axis data 00443 case bma180_cmd::eBIAS_Y: 00444 u16int_bias = (short) ((((unsigned short)chMSB)&0xFF)<<4)+((((unsigned short)chLSB)&0x0F)); 00445 break; 00446 // Bias Z axis data 00447 case bma180_cmd::eBIAS_Z: 00448 u16int_bias = (short) ((((unsigned short)chMSB)&0xFF)<<4)+((((unsigned short)chLSB)&0xF0)>>4); 00449 break; 00450 default : 00451 u16int_bias = 0; 00452 } 00453 return u16int_bias; 00454 }; 00455 00456 bool Bma180::read_byte_eeprom_sub20( char chADR, char* pchREGISTER, unsigned short iChipSelect, sub_handle sub_h ) 00457 { 00458 int iSpiErr = 0; 00459 bool bSuccess; 00460 char chCMD; 00461 00462 // Read register at specified adderss chADR 00463 //ensure CS is high 00464 iSpiErr += sub_spi_transfer( sub_h, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00465 //send read command 00466 chCMD = chADR | bma180_cmd::chFLAG_R; 00467 iSpiErr += sub_spi_transfer( sub_h, &chCMD, 0, 1, SS_CONF(iChipSelect,SS_L) ); 00468 iSpiErr += sub_spi_transfer( sub_h, 0, pchREGISTER, 1, SS_CONF(iChipSelect,SS_L) ); 00469 //ensure CS is high 00470 iSpiErr += sub_spi_transfer( sub_h, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00471 00472 if( iSpiErr == 0) 00473 { 00474 //successful operation 00475 bSuccess = true; 00476 } 00477 else 00478 { 00479 //SPI error 00480 bSuccess = false; 00481 } 00482 return bSuccess; 00483 }; 00484 00485 bool Bma180::write_bit_eeprom_sub20( char chADR, unsigned short iLSBOfByte, unsigned short iNumOfBits, char chBitSeq, unsigned short iChipSelect, sub_handle sub_h ) 00486 { 00487 char chCMD; //temporary character for building commands 00488 char chREGISTER; //temporary read status of register 00489 char chREGISTER_MODIFIED; 00490 int iSpiErr; 00491 char chMask; 00492 bool bSuccess; 00493 bool bEEReadSuccess; 00494 00495 //only one byte will be handled, thus iLSBOfByte + iNumOfBits > 8 means out of range 00496 if( iLSBOfByte + iNumOfBits <= 8 ) 00497 { 00498 iSpiErr = 0; 00499 bEEReadSuccess = true; 00500 00501 // Read register at specified address chADR 00502 chCMD = chADR | bma180_cmd::chFLAG_R; 00503 bEEReadSuccess &= read_byte_eeprom_sub20(chCMD, &chREGISTER, iChipSelect, sub_h ); 00504 00505 // Write the specified bit into register 00506 //Build mask, i.e. zero pad the respective points where we need to have 00507 if ( iNumOfBits < 8 ) 00508 { 00509 chMask = ~( ((1<<iNumOfBits)-1)<<iLSBOfByte ); 00510 } 00511 else 00512 { 00513 //as function of the range check above, it can only be 8 00514 chMask = 0x00; 00515 } 00516 //write specific register 00517 chREGISTER_MODIFIED = (chREGISTER&chMask ) | ( chBitSeq << iLSBOfByte ); 00518 //build up command to be written to register (note read flag is not set 00519 chCMD = chADR; 00520 iSpiErr += sub_spi_transfer( sub_h, &chCMD, 0, 1, SS_CONF(iChipSelect,SS_L) ); 00521 iSpiErr += sub_spi_transfer( sub_h, &chREGISTER_MODIFIED, 0, 1, SS_CONF(iChipSelect,SS_L) ); 00522 //ensure CS is high 00523 iSpiErr += sub_spi_transfer( sub_h, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00524 00525 // Check if register has been set (only verification) 00526 //send read command 00527 chCMD = chADR | bma180_cmd::chFLAG_R; 00528 bEEReadSuccess &= read_byte_eeprom_sub20(chCMD, &chREGISTER, iChipSelect, sub_h); 00529 00530 if( (iSpiErr == 0) && (bEEReadSuccess) ) 00531 { 00532 bSuccess = true; 00533 } 00534 else 00535 { 00536 //SPI communication error 00537 bSuccess = false; 00538 } 00539 } 00540 else 00541 { 00542 //out of range 00543 bSuccess = false; 00544 } 00545 return bSuccess; 00546 }; 00547 00548 void Bma180::confsens_on_sub20( OneSub20Config *pOneSub20Conf, char chFullscale, char chBandwidth ) 00549 { 00550 int iSpiErr; //Error code for Sub20 API 00551 int iChipSelect; 00552 bool bSuccess; 00553 char chCHIP_ID; 00554 char chALML_VER; 00555 char chCMD; 00556 char chREGSTATUS; 00557 unsigned short uiBiasX; 00558 unsigned short uiBiasY; 00559 unsigned short uiBiasZ; 00560 std::stringstream ss_errmsg; 00561 sub_handle handle_sub20; 00562 bool bEE_RWsuccess; 00563 00564 //retrieve handle for sub20 device 00565 handle_sub20 = pOneSub20Conf->handle_subdev; 00566 for( iChipSelect = 0; iChipSelect < bma180_cmd::iMAXNUM_OF_SENSORS; iChipSelect++ ) 00567 { 00568 pOneSub20Conf->Bma180Cluster[iChipSelect].iNumOfCalibMeas = 0; 00569 iSpiErr = 0; 00570 bEE_RWsuccess = true; 00571 //ensure CS is high 00572 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00573 //send read command 00574 chCMD = bma180_cmd::chADR_VER|bma180_cmd::chFLAG_R; 00575 iSpiErr += sub_spi_transfer( handle_sub20, &chCMD, 0, 1, SS_CONF(iChipSelect,SS_L) ); 00576 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chCHIP_ID, 1, SS_CONF(iChipSelect,SS_L) ); 00577 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chALML_VER, 1, SS_CONF(iChipSelect,SS_L) ); 00578 //ensure CS is high 00579 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00580 00581 //Verify if a BMA180 is connected on the respective ChipSelect 00582 if( (iSpiErr == 0) && (0<(unsigned short)chCHIP_ID) && (0<(unsigned short)chALML_VER) ) 00583 { 00584 ROS_INFO("-----------------------------------------"); 00585 ROS_INFO("BMA 180 - Chip Select %d", iChipSelect); 00586 ROS_INFO("CHIP ID : %u ", (unsigned short)chCHIP_ID); 00587 ROS_INFO("ALML Ver : %u ", (unsigned short)chALML_VER); 00588 00589 //call method to set ee_write flag 00590 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_CTRLREG0, 4, 1, bma180_cmd::chCMD_SET_EEW, iChipSelect, handle_sub20 ); 00591 //issue soft reset 00592 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_SOFTRESET, 0, 8, bma180_cmd::chCMD_SOFTRESET, iChipSelect, handle_sub20 ); 00593 //call method to set ee_write flag 00594 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_CTRLREG0, 4, 1, bma180_cmd::chCMD_SET_EEW, iChipSelect, handle_sub20 ); 00595 //change maxrange of sensor 00596 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_RANGE, 1, 3, chFullscale, iChipSelect, handle_sub20 ); 00597 bEE_RWsuccess &= read_byte_eeprom_sub20( bma180_cmd::chADR_RANGE, &chREGSTATUS, iChipSelect, handle_sub20 ); 00598 //Extract range 00599 pOneSub20Conf->Bma180Cluster[iChipSelect].dFullScaleRange = bma180_cmd::dFULLRANGELOOKUP[((unsigned short)((chREGSTATUS & 0x0E)>>1))]; 00600 //change sensor bandwidth 00601 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_BWTCS, 4, 4, chBandwidth, iChipSelect, handle_sub20 ); 00602 bEE_RWsuccess &= read_byte_eeprom_sub20( bma180_cmd::chADR_BWTCS, &chREGSTATUS, iChipSelect, handle_sub20 ); 00603 //Extract range 00604 pOneSub20Conf->Bma180Cluster[iChipSelect].dSensorBandwidth = bma180_cmd::dBWLOOKUP[((unsigned short)((chREGSTATUS & 0xF0)>>4))]; 00605 ROS_INFO("eeprom stored Fullrange : %f g ", pOneSub20Conf->Bma180Cluster[iChipSelect].dFullScaleRange); 00606 ROS_INFO("eeprom stored Bandwidth : %f Hz", pOneSub20Conf->Bma180Cluster[iChipSelect].dSensorBandwidth); 00607 ROS_INFO("-----------------------------------------"); 00608 00609 //Read bias that are currently stored in image 00610 bEE_RWsuccess &= read_biassettings( handle_sub20, iChipSelect, &uiBiasX, &uiBiasY, &uiBiasZ ); 00611 pOneSub20Conf->Bma180Cluster[iChipSelect].uiBiasImageX = uiBiasX; 00612 pOneSub20Conf->Bma180Cluster[iChipSelect].uiBiasImageY = uiBiasY; 00613 pOneSub20Conf->Bma180Cluster[iChipSelect].uiBiasImageZ = uiBiasZ; 00614 00615 if( bEE_RWsuccess ) 00616 { 00617 //Set flag that sensor has been initialized 00618 pOneSub20Conf->Bma180Cluster[iChipSelect].bConfigured = true; 00619 //successful operation 00620 bSuccess = true; 00621 } 00622 else 00623 { 00624 //Set flag that sensor has been initialized 00625 pOneSub20Conf->Bma180Cluster[iChipSelect].bConfigured = false; 00626 //successful operation 00627 bSuccess = false; 00628 } 00629 } 00630 else 00631 { 00632 ROS_INFO("-----------------------------------------"); 00633 ROS_INFO(" BMA 180 - Chip Select %d ", iChipSelect); 00634 ROS_INFO(" NO SENSOR DETECTED "); 00635 ROS_INFO("-----------------------------------------"); 00636 00637 //Set flag that sensor hasn't been initialized 00638 pOneSub20Conf->Bma180Cluster[iChipSelect].bConfigured = false; 00639 pOneSub20Conf->Bma180Cluster[iChipSelect].dFullScaleRange = 0; 00640 pOneSub20Conf->Bma180Cluster[iChipSelect].dSensorBandwidth = 0; 00641 pOneSub20Conf->Bma180Cluster[iChipSelect].uiBiasImageX = 0; 00642 pOneSub20Conf->Bma180Cluster[iChipSelect].uiBiasImageY = 0; 00643 pOneSub20Conf->Bma180Cluster[iChipSelect].uiBiasImageZ = 0; 00644 //unsuccessful operation 00645 bSuccess = false; 00646 } 00647 } 00648 }; 00649 00650 bool Bma180::read_biassettings( sub_handle handle_sub20, int iChipSelect, unsigned short* uiBiasX, unsigned short* uiBiasY, unsigned short* uiBiasZ ) 00651 { 00652 int iSpiErr; 00653 char chBiasXYZT[6]; 00654 bool bSuccess; 00655 char chCMD; 00656 char chCHIP_ID; 00657 char chALML_VER; 00658 00659 // Ensure BMA180 is connected 00660 //ensure CS is high 00661 iSpiErr = 0; 00662 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00663 00664 //send read command 00665 chCMD = bma180_cmd::chADR_VER|bma180_cmd::chFLAG_R; 00666 iSpiErr += sub_spi_transfer( handle_sub20, &chCMD, 0, 1, SS_CONF(iChipSelect,SS_L) ); 00667 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chCHIP_ID, 1, SS_CONF(iChipSelect,SS_L) ); 00668 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chALML_VER, 1, SS_CONF(iChipSelect,SS_L) ); 00669 00670 //ensure CS is high 00671 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00672 00673 //Verify if a BMA180 is connected on the respective ChipSelect 00674 if( (iSpiErr == 0) && (0 < (unsigned short)chCHIP_ID) && (0 < (unsigned short)chALML_VER) ) 00675 { 00676 //ensure CS is high 00677 //NOTE: Not executed in order to save one SPI transfer 00678 //iSpiErr = sub_spi_transfer( iterat->handle_subdev, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00679 //send read command 00680 chCMD = bma180_cmd::chADR_OFFSET_LSB1 | bma180_cmd::chFLAG_R; 00681 iSpiErr += sub_spi_transfer( handle_sub20, &chCMD, 0, 1, SS_CONF(iChipSelect,SS_L) ); 00682 iSpiErr += sub_spi_transfer( handle_sub20, 0, chBiasXYZT, 6, SS_CONF(iChipSelect,SS_L) ); 00683 //ensure CS is high 00684 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00685 00686 if( iSpiErr == 0 ) 00687 { 00688 (*uiBiasX) = bma180data_to_uint( chBiasXYZT[3], chBiasXYZT[0], bma180_cmd::eBIAS_X ); 00689 (*uiBiasY) = bma180data_to_uint( chBiasXYZT[4], chBiasXYZT[1], bma180_cmd::eBIAS_Y ); 00690 (*uiBiasZ) = bma180data_to_uint( chBiasXYZT[5], chBiasXYZT[1], bma180_cmd::eBIAS_Z ); 00691 bSuccess = true; 00692 } 00693 else 00694 { 00695 *uiBiasX = 0; 00696 *uiBiasY = 0; 00697 *uiBiasZ = 0; 00698 bSuccess = false; 00699 } 00700 } 00701 else 00702 { 00703 *uiBiasX = 0; 00704 *uiBiasY = 0; 00705 *uiBiasZ = 0; 00706 bSuccess = false; 00707 } 00708 return bSuccess; 00709 }; 00710 00711 bool Bma180::set_biassettings( sub_handle handle_sub20, int iChipSelect, unsigned short uiBiasX, unsigned short uiBiasY, unsigned short uiBiasZ, bool bWriteEEPROM ) 00712 { 00713 int iSpiErr; //Error code for Sub20 API 00714 bool bSuccess; 00715 char chCMD; 00716 char chCHIP_ID; 00717 char chALML_VER; 00718 char chMSB; 00719 char chLSB; 00720 bool bEE_RWsuccess; 00721 00722 // Ensure BMA180 is connected 00723 //ensure CS is high 00724 iSpiErr = 0; 00725 bEE_RWsuccess = true; 00726 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00727 //send read command 00728 chCMD = bma180_cmd::chADR_VER|bma180_cmd::chFLAG_R; 00729 iSpiErr += sub_spi_transfer( handle_sub20, &chCMD, 0, 1, SS_CONF(iChipSelect,SS_L) ); 00730 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chCHIP_ID, 1, SS_CONF(iChipSelect,SS_L) ); 00731 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chALML_VER, 1, SS_CONF(iChipSelect,SS_L) ); 00732 //ensure CS is high 00733 iSpiErr += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00734 00735 //Verify if a BMA180 is connected on the respective ChipSelect 00736 if( (iSpiErr == 0) && (0 < (unsigned short)chCHIP_ID) && (0 < (unsigned short)chALML_VER) ) 00737 { 00738 if( !bWriteEEPROM == true ) 00739 { 00740 // Write X axis offset 00741 chMSB = (char) ((uiBiasX&0xFF0)>>4); 00742 chLSB = (char) ((uiBiasX&0x0F)); 00743 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_OFFSET_X, 0, 8, chMSB, iChipSelect, handle_sub20 ); 00744 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_OFFSET_LSB1, 4, 4, chLSB, iChipSelect, handle_sub20 ); 00745 00746 // Write Y axis offset 00747 chMSB = (char) ((uiBiasY&0xFF0)>>4); 00748 chLSB = (char) ((uiBiasY&0x0F)); 00749 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_OFFSET_Y, 0, 8, chMSB, iChipSelect, handle_sub20 ); 00750 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_OFFSET_LSB2, 0, 4, chLSB, iChipSelect, handle_sub20 ); 00751 00752 // Write Z axis offset 00753 chMSB = (char) ((uiBiasZ&0xFF0)>>4); 00754 chLSB = (char) ((uiBiasZ&0x0F)); 00755 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_OFFSET_Z, 0, 8, chMSB, iChipSelect, handle_sub20 ); 00756 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_OFFSET_LSB2, 4, 4, chLSB, iChipSelect, handle_sub20 ); 00757 00758 if( bEE_RWsuccess ) 00759 { 00760 std::cout << "Writing to image " << std::endl; 00761 bSuccess = true; 00762 } 00763 else 00764 { 00765 bSuccess = false; 00766 std::cout << " !!!CANNOT WRITE IMAGE!!! " << std::endl; 00767 } 00768 } 00769 else 00770 { 00771 //Writing to the EEPROM is done by indirect write, i.e. setting values to image register 00772 //and then writing to the eeprom, which in fact reads the image register 00773 //Per write 16 bit from image to eeprom are written and only even addresses can used (see docu) 00774 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_EE_GAIN_Z, 0, 8, 0x00, iChipSelect, handle_sub20 ); 00775 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_EE_OFFSET_LSB2, 0, 8, 0x00, iChipSelect, handle_sub20 ); 00776 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_EE_OFFSET_X, 0, 8, 0x00, iChipSelect, handle_sub20 ); 00777 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::chADR_EE_OFFSET_Z, 0, 8, 0x00, iChipSelect, handle_sub20 ); 00778 00779 if( bEE_RWsuccess ) 00780 { 00781 std::cout << "***************EEPROM written ******************** " << std::endl; 00782 bSuccess = true; 00783 } 00784 else 00785 { 00786 bSuccess = false; 00787 } 00788 } 00789 } 00790 else 00791 { 00792 //unsuccessful operation 00793 bSuccess = false; 00794 } 00795 return bSuccess; 00796 }; 00797 00798 00799 void Bma180::set_calibstatus( bool bCalibrate ) 00800 { 00801 if( bCalibrate == true ) 00802 { 00803 std::string myAnswer; 00804 std::cout << "Sensors shall be calibrated <Y/N>? "; 00805 std::getline( std::cin, myAnswer ); 00806 if( (0 == myAnswer.find('Y')) || (0 == myAnswer.find('y')) ) 00807 { 00808 unsigned short myCS; 00809 std::cout << "Specify ChipSelect <0..4>? "; 00810 if( std::cin >> myCS ) 00811 { 00812 if( myCS < bma180_cmd::iMAXNUM_OF_SENSORS ) 00813 { 00814 bExecuteCalibration = true; 00815 bCalibrationCompleted = false; 00816 iCalib_CS = myCS; 00817 } 00818 else 00819 { 00820 bExecuteCalibration = false; 00821 bCalibrationCompleted = true; 00822 } 00823 } 00824 else 00825 { 00826 bExecuteCalibration = false; 00827 bCalibrationCompleted = true; 00828 std::cin.clear(); 00829 } 00830 } 00831 else 00832 { 00833 bExecuteCalibration = false; 00834 bCalibrationCompleted = true; 00835 } 00836 } 00837 else 00838 { 00839 bExecuteCalibration = false; 00840 bCalibrationCompleted = true; 00841 } 00842 }; 00843 00844 00845 00846 // ---------- 00847 // -- MAIN -- 00848 // ---------- 00849 int main( int argc, char **argv ) 00850 { 00851 int count = 1, i = 0; 00852 00853 //ROS initialization and publish/subscribe setup 00854 ros::init(argc, argv, "bma180"); 00855 ros::NodeHandle nh; 00856 ros::Publisher bma180_pub = nh.advertise<bma180::bma180meas>("bma180", 100); 00857 00858 //Parameter Server values 00859 double dMaxAcc_g, dRate_Hz, dBandwidth_Hz; 00860 bool bCalibrate; 00861 std::string sSub20Serial; 00862 00863 // Read parameters from server - if parameters are not available, the node 00864 // is initialized with default 00865 if( nh.getParam("/bma180/max_acc_g", dMaxAcc_g) == false ) 00866 { 00867 dMaxAcc_g = bma180_cmd::dDEFAULT_MAXACC_g; 00868 }; 00869 if( nh.getParam("/bma180/bandwidth_Hz", dBandwidth_Hz) == false ) 00870 { 00871 dBandwidth_Hz = bma180_cmd::dDEFAULT_BANDWIDTH_Hz; 00872 }; 00873 if( nh.getParam("/bma180/rate_Hz", dRate_Hz) == false ) 00874 { 00875 dRate_Hz = bma180_cmd::dDEFAULT_RATE_Hz; 00876 }; 00877 if( nh.getParam("/bma180/calibrate", bCalibrate) == false ) 00878 { 00879 bCalibrate = bma180_cmd::bDEFAULT_CALIBRATE; 00880 }; 00881 if( nh.getParam("/bma180/sub20serial", sSub20Serial) == false ) 00882 { 00883 sSub20Serial = bma180_cmd::sSUB20SERIAL; 00884 }; 00885 00886 Bma180 bma180_attached( dMaxAcc_g, dBandwidth_Hz, bCalibrate, dRate_Hz, sSub20Serial ); 00887 OneBma180Meas sOneMeas; 00888 bma180::bma180meas msg; 00889 std::list<OneBma180Meas> measurements_list; 00890 00891 00892 // Run sensor node 00893 00894 //set loop rate for measurement polling 00895 ros::Rate loop_rate(dRate_Hz); 00896 00897 while( nh.ok() ) 00898 { 00899 //initiate a measurement on BMA180ies 00900 try 00901 { 00902 bma180_attached.GetMeasurements(measurements_list); 00903 } 00904 catch( std::string strType ) 00905 { 00906 std::cout << " An exception occurred: " << strType << std::endl; 00907 std::exit(1); 00908 } 00909 00910 while( !measurements_list.empty() ) 00911 { 00912 sOneMeas = measurements_list.back(); 00913 measurements_list.pop_back(); 00914 //only publish if a successful measurement was received 00915 if( sOneMeas.bMeasAvailable == true ) 00916 { 00917 msg.strIdSubDev = sOneMeas.strSerial; 00918 00919 // collect all available chipselect values into one message 00920 for( i = 0; i < sOneMeas.iNumAccels; i++ ) 00921 { 00922 msg.iChipSelect.push_back( sOneMeas.iChipSelect[i] ); 00923 msg.fAccelX.push_back( sOneMeas.dAccX[i] ); 00924 msg.fAccelY.push_back( sOneMeas.dAccY[i] ); 00925 msg.fAccelZ.push_back( sOneMeas.dAccZ[i] ); 00926 } 00927 msg.header.stamp = sOneMeas.dtomeas; 00928 bma180_pub.publish( msg ); // publish message 00929 00930 // clear the message values after publishing to avoid accumulation of further values on subsequent messages. 00931 msg.iChipSelect.clear(); 00932 msg.fAccelX.clear(); 00933 msg.fAccelY.clear(); 00934 msg.fAccelZ.clear(); 00935 } 00936 } 00937 00938 ros::spinOnce(); 00939 loop_rate.sleep(); 00940 ++count; 00941 } 00942 } 00943 00944