$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, Nikhil Deshpande, Philip Roan, Robert Bosch LLC 00035 */ 00036 #include <iostream> 00037 #include <string> 00038 #include <ros/ros.h> 00039 #include "bma180/bma180s.h" 00040 #include <sstream> 00041 #include <ros/time.h> 00042 #include <math.h> 00043 #include <vector> 00044 00045 #define ROS_INFO printf 00046 #define ROS_WARN printf 00047 #define ROS_ERROR printf 00048 00049 Bma180::Bma180( double max_acceleration_g, double dBandwidth_Hz, bool bCalibrate, double dRate_Hz, std::string sSub20Serial ): 00050 bSubDeviceOpen (false), 00051 bSubDeviceConfigured (false) 00052 { 00053 int error_code; // Sub20 error code 00054 int iSPI_cfg_set; //Set SPI config 00055 int iSPI_cfg_get; //Get SPI config 00056 int iNumOfRanges; 00057 int iElCount; 00058 std::stringstream ss_errmsg; 00059 std::string ss_config, sub20Serial; 00060 sub_device sub20dev; 00061 sub_handle sub20handle; 00062 OneSub20Config OneSub20Configuration; 00063 00064 printf("Max acceleration entered: %f [g].\n", max_acceleration_g); 00065 printf("Sensor bandwidth entered: %f [Hz].\n", dBandwidth_Hz); 00066 printf("Sensor Reading Rate entered: %f [Hz].\n", dRate_Hz); 00067 00068 //Retrieve calibration data from user 00069 set_calibstatus( bCalibrate ); 00070 00071 // Evaluate the accelerometer range to be selected 00072 iNumOfRanges = sizeof(bma180_cmd::COMMAND_FULLSCALE_G) / sizeof(char); 00073 iElCount = 0; 00074 while( (max_acceleration_g > bma180_cmd::dFULLRANGELOOKUP[iElCount]) && (iElCount < iNumOfRanges) ) 00075 { 00076 iElCount++; 00077 }; 00078 printf("Range chosen: %f [g].\n", bma180_cmd::dFULLRANGELOOKUP[iElCount]); 00079 00080 chMaxAccRange_selected = bma180_cmd::COMMAND_FULLSCALE_G[iElCount]; 00081 00082 // Evaluate the bandwidth to be selected 00083 iNumOfRanges = sizeof(bma180_cmd::COMMAND_BANDWIDTH_HZ) / sizeof(char); 00084 iElCount = 0; 00085 while( (dBandwidth_Hz > bma180_cmd::dBWLOOKUP[iElCount]) && (iElCount < iNumOfRanges) ) 00086 { 00087 iElCount++; 00088 }; 00089 printf("Range chosen BW: %f.\n", bma180_cmd::dBWLOOKUP[iElCount]); 00090 00091 chBW_selected = bma180_cmd::COMMAND_BANDWIDTH_HZ[iElCount]; 00092 00093 // Open connected Sub20 Devices 00094 sub20dev = 0; 00095 sub20dev = sub_find_devices(sub20dev); 00096 while( sub20dev != 0 ) 00097 { 00098 sub20handle = sub_open( sub20dev ); 00099 // on success, sub_open returns non-zero handle 00100 if( sub20handle > 0 ) 00101 { 00102 sub20Serial.clear(); 00103 sub20Serial.resize( bma180_cmd::uSERIALNUMLENGTH ); 00104 sub_get_serial_number( sub20handle, const_cast<char*>(sub20Serial.c_str()), sub20Serial.size() ); 00105 printf( "Serial Number: %s.\n", sub20Serial.c_str() ); 00106 if( strcmp(sub20Serial.c_str(), sSub20Serial.c_str()) == 0 ) 00107 { 00108 subhndl = sub20handle; 00109 00110 // Configure Sub20 device 00111 std::cout << "---Initializing SPI Interface---" << std::endl;; 00112 // Read current SPI configuration 00113 error_code = sub_spi_config( sub20handle, 0, &iSPI_cfg_get ); 00114 std::cout << "Sub SPI config : " << iSPI_cfg_get << std::endl; 00115 00116 // Important: The SPI interface does not work properly at higher frequencies, i.e. > 2MHz 00117 // SET: Polarity Fall, SetupSmpl, MSB first, 2MHZ 00118 iSPI_cfg_set = SPI_ENABLE | SPI_CPOL_FALL | SPI_SETUP_SMPL | SPI_MSB_FIRST | SPI_CLK_2MHZ; 00119 // Configure SPI 00120 error_code = sub_spi_config( sub20handle, iSPI_cfg_set, 0 ); 00121 // Read current SPI configuration 00122 error_code = sub_spi_config( sub20handle, 0, &iSPI_cfg_get ); 00123 // verify if sub20 device has accepted the configuration 00124 if( iSPI_cfg_get == iSPI_cfg_set ) 00125 { 00126 std::cout<< "SPI Configuration: " << iSPI_cfg_set << " successfully stored." << std::endl; 00127 00128 // Subdevice has been configured successfully 00129 OneSub20Configuration.bSubSPIConfigured = true; 00130 OneSub20Configuration.handle_subdev = sub20handle; 00131 00132 // Configure Sensors on Sub20 00133 confsens_on_sub20( &OneSub20Configuration, chMaxAccRange_selected, chBW_selected); 00134 } 00135 else 00136 { 00137 ROS_INFO("ERROR! SPI Configuration %d not accepted by device.\n", iSPI_cfg_set); 00138 00139 // Subdevice could not be configured 00140 OneSub20Configuration.bSubSPIConfigured = false; 00141 } 00142 if( OneSub20Configuration.bSubSPIConfigured ) 00143 { 00144 // string needs to be cleared otherwise conversion is going wrong 00145 serial_number.clear(); 00146 serial_number.resize( bma180_cmd::uSERIALNUMLENGTH ); 00147 sub_get_serial_number( sub20handle, const_cast<char*>(serial_number.c_str()), serial_number.size() ); 00148 OneSub20Configuration.strSub20Serial = serial_number; 00149 OneSub20Configuration.subdev = sub20dev; 00150 std::cout << "Device Handle: " << OneSub20Configuration.handle_subdev << std::endl; 00151 std::cout << "Serial Number: " << OneSub20Configuration.strSub20Serial << std::endl; 00152 00153 // Push element onto list of subdevices 00154 Sub20Device_list.push_back( OneSub20Configuration ); 00155 std::cout << "Publishing to topic /bma180." << std::endl; 00156 } 00157 break; 00158 } 00159 else 00160 { 00161 sub_close( sub20handle ); 00162 } 00163 } 00164 // find next device, sub_find_devices using current provides next 00165 sub20dev = sub_find_devices( sub20dev ); 00166 } 00167 }; 00168 00169 Bma180::~Bma180() 00170 { 00171 int error_code; 00172 OneSub20Config OneSub20Configuration; 00173 00174 // close opened subdevices 00175 00176 // Disable SPI 00177 error_code = sub_spi_config( subhndl, 0, 0 ); 00178 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 << std::endl; 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 error_code, dummy, j = 0; 00197 bool SPIMeas = false; 00198 OneBma180Meas sMeas; 00199 //ros::Time dtomeas; 00200 char chCMD; 00201 std::stringstream ss_errmsg; 00202 int chip_select; 00203 std::list<OneSub20Config>::iterator iterat; 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( chip_select = 0; chip_select < bma180_cmd::MAX_NUM_SENSORS; chip_select++ ) 00219 { 00220 // verify if sensor is available on respective chipselect 00221 if( iterat->Bma180Cluster[chip_select].bConfigured == true ) 00222 { 00223 error_code = 0; 00224 // NOTE: Not executed in order to save one SPI transfer 00225 // //ensure CS is high 00226 // //error_code = sub_spi_transfer( iterat->handle_subdev, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00227 // //send read command 00228 chCMD = bma180_cmd::ADDRESS_ACCLXYZ | bma180_cmd::FLAG_R; 00229 error_code += sub_spi_transfer( iterat->handle_subdev, &chCMD, 0, 1, SS_CONF(chip_select,SS_L) ); 00230 error_code += sub_spi_transfer( iterat->handle_subdev, 0, chACC_XYZ, 7, SS_CONF(chip_select,SS_L) ); 00231 // ensure CS is high 00232 error_code += sub_spi_transfer( iterat->handle_subdev, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00233 00234 if( error_code == 0 ) 00235 { 00236 SPIMeas = true; 00237 dAccX = bma180data_to_double(chACC_XYZ[1], chACC_XYZ[0], bma180_cmd::eACCEL, &uiRawX, iterat->Bma180Cluster[chip_select].dFullScaleRange ); 00238 dAccY = bma180data_to_double(chACC_XYZ[3], chACC_XYZ[2], bma180_cmd::eACCEL, &uiRawY, iterat->Bma180Cluster[chip_select].dFullScaleRange ); 00239 dAccZ = bma180data_to_double(chACC_XYZ[5], chACC_XYZ[4], bma180_cmd::eACCEL, &uiRawZ, iterat->Bma180Cluster[chip_select].dFullScaleRange ); 00240 dTemp = bma180data_to_double(chACC_XYZ[6], chACC_XYZ[6], bma180_cmd::eTEMP, &dummy, iterat->Bma180Cluster[chip_select].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.chip_select[j] = chip_select; 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( chip_select == 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[chip_select].uiBiasImageX << " " << iterat->Bma180Cluster[chip_select].uiBiasImageY << " " << iterat->Bma180Cluster[chip_select].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 00271 calib_bma180.get_estbiases(&dEstBiasX, &dEstBiasY, &dEstBiasZ); 00272 std::cout << "estimated biases : " << dEstBiasX << " " << dEstBiasY << " " << dEstBiasZ << std::endl; 00273 00274 // calculate adjustment 00275 // +0.5 for typecast to get propper rounding 00276 // 2048: Bias has 12 bit, thus halfrange is 2^11 where as bias corr scales by range 00277 int iBcorrX, iBcorrY, iBcorrZ; 00278 iBcorrX = (short)( dEstBiasX / iterat->Bma180Cluster[chip_select].dFullScaleRange * 2048 + 0.5 ); 00279 iBcorrY = (short)( dEstBiasY / iterat->Bma180Cluster[chip_select].dFullScaleRange * 2048 + 0.5 ) ; 00280 iBcorrZ = (short)( (dEstBiasZ - 1) / iterat->Bma180Cluster[chip_select].dFullScaleRange * 2048 + 0.5 ) ; 00281 00282 std::cout << "Bias adjustments [X Y Z] " << iBcorrX << " " << iBcorrY << " " << iBcorrZ << std::endl; 00283 std::cout << "Image values before adjustments " << iterat->Bma180Cluster[chip_select].uiBiasImageX << " " << iterat->Bma180Cluster[chip_select].uiBiasImageY << " " << iterat->Bma180Cluster[chip_select].uiBiasImageZ << std::endl; 00284 uiBcorrX = (unsigned short)( iterat->Bma180Cluster[chip_select].uiBiasImageX - ((short)( dEstBiasX / bma180_cmd::dFULLRANGELOOKUP[6] * 2048 )) ); 00285 uiBcorrY = (unsigned short)( iterat->Bma180Cluster[chip_select].uiBiasImageY - ((short)( dEstBiasY / bma180_cmd::dFULLRANGELOOKUP[6] * 2048 )) ); 00286 uiBcorrZ = (unsigned short)( iterat->Bma180Cluster[chip_select].uiBiasImageZ - ((short)( (dEstBiasZ - 1) / bma180_cmd::dFULLRANGELOOKUP[6] * 2048 )) ); 00287 00288 std::cout << "corrected biases " << uiBcorrX << " " << uiBcorrY << " " << uiBcorrZ << std::endl; 00289 00290 // Write to image 00291 if( !set_biassettings( iterat->handle_subdev, chip_select, uiBcorrX, uiBcorrY, uiBcorrZ, false) ) 00292 { 00293 bExecuteCalibration = false; 00294 throw std::string( "Bias corrections cannot be written to image. Calibration procedure aborted." ); 00295 } 00296 00297 // Activate verification 00298 if( !calib_bma180.biasverify() ) 00299 { 00300 bExecuteCalibration = false; 00301 throw std::string( "Bias verification cannot be executed. Calibration procedure aborted." ); 00302 } 00303 } 00304 00305 if( calib_bma180.calibsens_completed() && calib_bma180.verification_active() && calib_bma180.verification_completed() ) 00306 { 00307 std::cout << "Verifying biases..." << 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, chip_select, 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.\n"); 00334 00335 } 00336 else 00337 { 00338 ROS_INFO("EEPROM write aborted.\n"); 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 because the calibration values are too large. Calibration procedure aborted."); 00346 } 00347 // We are done with calibration 00348 bExecuteCalibration = false; 00349 std::cout << "Calibration completed successfully." << 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, please connect only one Sub20 device during calibration."); 00358 } 00359 } 00360 } 00361 else 00362 { 00363 throw std::string( "There has been an SPI communication error. Continuing attempts to communicate with the device will be made." ); 00364 } 00365 } // config verify 00366 } // scanning through all the chipselects 00367 } 00368 00369 // Only publish data after all data for all chipSelects is collected 00370 if( SPIMeas ) 00371 { 00372 //sMeas.dtomeas = ros::Time::now(); 00373 sMeas.bMeasAvailable = true; 00374 sMeas.serial_number = iterat->strSub20Serial; 00375 00376 // Push measurement onto heap 00377 list_meas.push_back( sMeas ); 00378 } 00379 else 00380 { 00381 throw std::string( "SUB20 connected but not configured. A restart of the ROS node is suggested."); 00382 } 00383 } // sub20 for loop 00384 }; 00385 00386 double Bma180::bma180data_to_double( char chMSB, char chLSB, bma180_cmd::eSensorType eSensor, int *raw, double dAccScale ) 00387 { 00388 short s16int; // 2 byte int to build message 00389 double dSensorMeas; // Scaled sensor measurement 00390 00391 switch( eSensor ) 00392 { 00393 // Retrieve Accel Data 00394 case bma180_cmd::eACCEL: 00395 // verify if pos or neg 00396 if( (chMSB & 0x80) == 0 ) 00397 { 00398 // positive number 00399 s16int = (short)( (((unsigned short)chMSB) & 0xFF) << 6) + ((((unsigned short)chLSB) & 0xFC) >> 2 ); 00400 } 00401 else 00402 { 00403 // negative number 00404 // set MSB (sign) to zero and build 2 complement unsigned; offset 8192 for 2^13 00405 s16int = (short)( ((((unsigned short)chMSB) & 0x7F ) << 6 ) + ((((unsigned short)chLSB) & 0xFC) >> 2 ) - 8192 ); 00406 } 00407 dSensorMeas = ( ((double)s16int) / 8192 ) * dAccScale; 00408 break; 00409 00410 // Convert Temperature Data 00411 case bma180_cmd::eTEMP: 00412 // verify if pos or neg 00413 if( (chLSB & 0x80) == 0 ) 00414 { 00415 // positive number 00416 s16int = (short)( ((unsigned short)chLSB) & 0xFF ); 00417 } 00418 else 00419 { 00420 // negative number 00421 // set MSB (sign) to zero and build 2 complement unsigned; offset 128 for 2^7 00422 s16int = (short)( (((unsigned short)chLSB) & 0x7F ) - 128 ); 00423 }; 00424 dSensorMeas = ( ( (double)s16int) / 8192 ) * 2; 00425 break; 00426 00427 default : 00428 dSensorMeas = 0; 00429 } 00430 *raw = s16int; 00431 return (dSensorMeas); 00432 }; 00433 00434 unsigned short Bma180::bma180data_to_uint( char chMSB, char chLSB, bma180_cmd::eSensorType eSensor ) 00435 { 00436 unsigned short u16int_bias; // 2 byte int to build message 00437 switch( eSensor ) 00438 { 00439 // Bias X axis data 00440 case bma180_cmd::eBIAS_X: 00441 u16int_bias = (short) ((((unsigned short)chMSB)&0xFF)<<4)+((((unsigned short)chLSB)&0xF0)>>4); 00442 break; 00443 00444 // Bias Y axis data 00445 case bma180_cmd::eBIAS_Y: 00446 u16int_bias = (short) ((((unsigned short)chMSB)&0xFF)<<4)+((((unsigned short)chLSB)&0x0F)); 00447 break; 00448 00449 // Bias Z axis data 00450 case bma180_cmd::eBIAS_Z: 00451 u16int_bias = (short) ((((unsigned short)chMSB)&0xFF)<<4)+((((unsigned short)chLSB)&0xF0)>>4); 00452 break; 00453 default : 00454 u16int_bias = 0; 00455 } 00456 return (u16int_bias); 00457 }; 00458 00459 bool Bma180::read_byte_eeprom_sub20( char chADR, char* pchREGISTER, unsigned short chip_select, sub_handle sub_h ) 00460 { 00461 int error_code = 0; 00462 bool bSuccess; 00463 char chCMD; 00464 00465 // Read register at specified adderss chADR 00466 00467 // ensure CS is high 00468 error_code += sub_spi_transfer( sub_h, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00469 // send read command 00470 chCMD = chADR | bma180_cmd::FLAG_R; 00471 error_code += sub_spi_transfer( sub_h, &chCMD, 0, 1, SS_CONF(chip_select,SS_L) ); 00472 error_code += sub_spi_transfer( sub_h, 0, pchREGISTER, 1, SS_CONF(chip_select,SS_L) ); 00473 // ensure CS is high 00474 error_code += sub_spi_transfer( sub_h, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00475 00476 if (error_code == 0) 00477 { 00478 // successful operation 00479 bSuccess = true; 00480 } 00481 else 00482 { 00483 // SPI error 00484 bSuccess = false; 00485 } 00486 return (bSuccess); 00487 }; 00488 00489 bool Bma180::write_bit_eeprom_sub20( char chADR, unsigned short iLSBOfByte, unsigned short iNumOfBits, char chBitSeq, unsigned short chip_select, sub_handle sub_h ) 00490 { 00491 char chCMD; // temporary character for building commands 00492 char chREGISTER; // temporary read status of register 00493 char chREGISTER_MODIFIED; 00494 int error_code; 00495 char chMask; 00496 bool bSuccess; 00497 bool bEEReadSuccess; 00498 00499 // only one byte will be handled, thus iLSBOfByte + iNumOfBits > 8 means out of range 00500 if ( iLSBOfByte + iNumOfBits <= 8 ) 00501 { 00502 error_code = 0; 00503 bEEReadSuccess = true; 00504 00505 // Read register at specified address chADR 00506 chCMD = chADR | bma180_cmd::FLAG_R; 00507 bEEReadSuccess &= read_byte_eeprom_sub20(chCMD, &chREGISTER, chip_select, sub_h ); 00508 00509 // Write the specified bit into register 00510 // Build mask, i.e. zero pad the respective points where we need to have 00511 if ( iNumOfBits < 8 ) 00512 { 00513 chMask = ~( ((1 << iNumOfBits) - 1) << iLSBOfByte ); 00514 } 00515 else 00516 { 00517 // as function of the range check above, it can only be 8 00518 chMask = 0x00; 00519 } 00520 // write specific register 00521 chREGISTER_MODIFIED = ( chREGISTER & chMask ) | ( chBitSeq << iLSBOfByte ); 00522 // build up command to be written to register (note read flag is not set 00523 chCMD = chADR; 00524 error_code += sub_spi_transfer( sub_h, &chCMD, 0, 1, SS_CONF(chip_select,SS_L) ); 00525 error_code += sub_spi_transfer( sub_h, &chREGISTER_MODIFIED, 0, 1, SS_CONF(chip_select,SS_L) ); 00526 // ensure CS is high 00527 error_code += sub_spi_transfer( sub_h, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00528 00529 // Check if register has been set (only verification) 00530 00531 // send read command 00532 chCMD = chADR | bma180_cmd::FLAG_R; 00533 bEEReadSuccess &= read_byte_eeprom_sub20(chCMD, &chREGISTER, chip_select, sub_h); 00534 00535 if( (error_code == 0) && (bEEReadSuccess) ) 00536 { 00537 bSuccess = true; 00538 } 00539 else 00540 { 00541 // SPI communication error 00542 bSuccess = false; 00543 } 00544 } 00545 else 00546 { 00547 // out of range 00548 bSuccess = false; 00549 } 00550 return bSuccess; 00551 }; 00552 00553 void Bma180::confsens_on_sub20( OneSub20Config *pOneSub20Conf, char chFullscale, char chBandwidth ) 00554 { 00555 int error_code; 00556 int chip_select; 00557 bool bSuccess; 00558 char chCHIP_ID; 00559 char chALML_VER; 00560 char chCMD; 00561 char chREGSTATUS; 00562 unsigned short uiBiasX; 00563 unsigned short uiBiasY; 00564 unsigned short uiBiasZ; 00565 std::stringstream ss_errmsg; 00566 sub_handle handle_sub20; 00567 bool bEE_RWsuccess; 00568 00569 // retrieve handle for sub20 device 00570 handle_sub20 = pOneSub20Conf->handle_subdev; 00571 for( chip_select = 0; chip_select < bma180_cmd::MAX_NUM_SENSORS; chip_select++ ) 00572 { 00573 pOneSub20Conf->Bma180Cluster[chip_select].iNumOfCalibMeas = 0; 00574 error_code = 0; 00575 bEE_RWsuccess = true; 00576 // ensure CS is high 00577 error_code += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00578 // send read command 00579 chCMD = bma180_cmd::ADDRESS_VER | bma180_cmd::FLAG_R; 00580 error_code += sub_spi_transfer( handle_sub20, &chCMD, 0, 1, SS_CONF(chip_select,SS_L) ); 00581 error_code += sub_spi_transfer( handle_sub20, 0, &chCHIP_ID, 1, SS_CONF(chip_select,SS_L) ); 00582 error_code += sub_spi_transfer( handle_sub20, 0, &chALML_VER, 1, SS_CONF(chip_select,SS_L) ); 00583 // ensure CS is high 00584 error_code += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00585 00586 // Verify if a BMA180 is connected on the respective ChipSelect 00587 if( error_code == 0 && 0 < (unsigned short)chCHIP_ID && 0 < (unsigned short)chALML_VER ) 00588 { 00589 ROS_INFO("BMA 180 - Chip Select %d\n", chip_select); 00590 ROS_INFO("CHIP ID: %u\n", (unsigned short)chCHIP_ID); 00591 ROS_INFO("ALML Ver: %u\n", (unsigned short)chALML_VER); 00592 00593 // call method to set ee_write flag 00594 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::ADDRESS_CTRLREG0, 4, 1, bma180_cmd::COMMAND_SET_EEW, chip_select, handle_sub20 ); 00595 // issue soft reset 00596 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::ADDRESS_SOFTRESET, 0, 8, bma180_cmd::COMMAND_SOFTRESET, chip_select, handle_sub20 ); 00597 // call method to set ee_write flag 00598 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::ADDRESS_CTRLREG0, 4, 1, bma180_cmd::COMMAND_SET_EEW, chip_select, handle_sub20 ); 00599 // change maxrange of sensor 00600 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::ADDRESS_RANGE, 1, 3, chFullscale, chip_select, handle_sub20 ); 00601 bEE_RWsuccess &= read_byte_eeprom_sub20( bma180_cmd::ADDRESS_RANGE, &chREGSTATUS, chip_select, handle_sub20 ); 00602 // Extract range 00603 pOneSub20Conf->Bma180Cluster[chip_select].dFullScaleRange = bma180_cmd::dFULLRANGELOOKUP[((unsigned short)((chREGSTATUS & 0x0E)>>1))]; 00604 // change sensor bandwidth 00605 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::ADDRESS_BWTCS, 4, 4, chBandwidth, chip_select, handle_sub20 ); 00606 bEE_RWsuccess &= read_byte_eeprom_sub20( bma180_cmd::ADDRESS_BWTCS, &chREGSTATUS, chip_select, handle_sub20 ); 00607 // Extract range 00608 pOneSub20Conf->Bma180Cluster[chip_select].dSensorBandwidth = bma180_cmd::dBWLOOKUP[((unsigned short)((chREGSTATUS & 0xF0)>>4))]; 00609 ROS_INFO("EEPROM stored Fullrange: %f [g]\n", pOneSub20Conf->Bma180Cluster[chip_select].dFullScaleRange); 00610 ROS_INFO("EEPROM stored Bandwidth: %f [Hz]\n", pOneSub20Conf->Bma180Cluster[chip_select].dSensorBandwidth); 00611 00612 // Read bias that are currently stored in image 00613 bEE_RWsuccess &= read_biassettings( handle_sub20, chip_select, &uiBiasX, &uiBiasY, &uiBiasZ ); 00614 pOneSub20Conf->Bma180Cluster[chip_select].uiBiasImageX = uiBiasX; 00615 pOneSub20Conf->Bma180Cluster[chip_select].uiBiasImageY = uiBiasY; 00616 pOneSub20Conf->Bma180Cluster[chip_select].uiBiasImageZ = uiBiasZ; 00617 00618 if( bEE_RWsuccess ) 00619 { 00620 // Set flag that sensor has been initialized 00621 pOneSub20Conf->Bma180Cluster[chip_select].bConfigured = true; 00622 // successful operation 00623 bSuccess = true; 00624 } 00625 else 00626 { 00627 // Set flag that sensor has been initialized 00628 pOneSub20Conf->Bma180Cluster[chip_select].bConfigured = false; 00629 // unsuccessful operation 00630 bSuccess = false; 00631 } 00632 } 00633 else 00634 { 00635 ROS_INFO("BMA 180 %d: No sensor detected\n", chip_select); 00636 00637 // Set flag that sensor hasn't been initialized 00638 pOneSub20Conf->Bma180Cluster[chip_select].bConfigured = false; 00639 pOneSub20Conf->Bma180Cluster[chip_select].dFullScaleRange = 0; 00640 pOneSub20Conf->Bma180Cluster[chip_select].dSensorBandwidth = 0; 00641 pOneSub20Conf->Bma180Cluster[chip_select].uiBiasImageX = 0; 00642 pOneSub20Conf->Bma180Cluster[chip_select].uiBiasImageY = 0; 00643 pOneSub20Conf->Bma180Cluster[chip_select].uiBiasImageZ = 0; 00644 // unsuccessful operation 00645 bSuccess = false; 00646 } 00647 } 00648 }; 00649 00650 bool Bma180::read_biassettings( sub_handle handle_sub20, int chip_select, unsigned short* uiBiasX, unsigned short* uiBiasY, unsigned short* uiBiasZ ) 00651 { 00652 int error_code; 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 00661 // ensure CS is high 00662 error_code = 0; 00663 error_code += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00664 // send read command 00665 chCMD = bma180_cmd::ADDRESS_VER|bma180_cmd::FLAG_R; 00666 error_code += sub_spi_transfer( handle_sub20, &chCMD, 0, 1, SS_CONF(chip_select,SS_L) ); 00667 error_code += sub_spi_transfer( handle_sub20, 0, &chCHIP_ID, 1, SS_CONF(chip_select,SS_L) ); 00668 error_code += sub_spi_transfer( handle_sub20, 0, &chALML_VER, 1, SS_CONF(chip_select,SS_L) ); 00669 // ensure CS is high 00670 error_code += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00671 00672 // Verify if a BMA180 is connected on the respective chip select line 00673 if( (error_code == 0) && ( 0 < (unsigned short)chCHIP_ID) && ( 0 < (unsigned short)chALML_VER) ) 00674 { 00675 // ensure CS is high 00676 // NOTE: Not executed in order to save one SPI transfer 00677 //error_code = sub_spi_transfer( iterat->handle_subdev, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00678 // send read command 00679 chCMD = bma180_cmd::ADDRESS_OFFSET_LSB1 | bma180_cmd::FLAG_R; 00680 error_code += sub_spi_transfer( handle_sub20, &chCMD, 0, 1, SS_CONF(chip_select,SS_L) ); 00681 error_code += sub_spi_transfer( handle_sub20, 0, chBiasXYZT, 6, SS_CONF(chip_select,SS_L) ); 00682 // ensure CS is high 00683 error_code += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00684 00685 if( error_code == 0 ) 00686 { 00687 (*uiBiasX) = bma180data_to_uint( chBiasXYZT[3], chBiasXYZT[0], bma180_cmd::eBIAS_X ); 00688 (*uiBiasY) = bma180data_to_uint( chBiasXYZT[4], chBiasXYZT[1], bma180_cmd::eBIAS_Y ); 00689 (*uiBiasZ) = bma180data_to_uint( chBiasXYZT[5], chBiasXYZT[1], bma180_cmd::eBIAS_Z ); 00690 bSuccess = true; 00691 } 00692 else 00693 { 00694 (*uiBiasX) = 0; 00695 (*uiBiasY) = 0; 00696 (*uiBiasZ) = 0; 00697 bSuccess = false; 00698 } 00699 } 00700 else 00701 { 00702 (*uiBiasX) = 0; 00703 (*uiBiasY) = 0; 00704 (*uiBiasZ) = 0; 00705 bSuccess = false; 00706 } 00707 return bSuccess; 00708 }; 00709 00710 bool Bma180::set_biassettings( sub_handle handle_sub20, int chip_select, unsigned short uiBiasX, unsigned short uiBiasY, unsigned short uiBiasZ, bool bWriteEEPROM ) 00711 { 00712 int error_code; //Error code for Sub20 API 00713 bool bSuccess; 00714 char chCMD; 00715 char chCHIP_ID; 00716 char chALML_VER; 00717 char chMSB; 00718 char chLSB; 00719 bool bEE_RWsuccess; 00720 00721 // Ensure BMA180 is connected 00722 00723 // ensure CS is high 00724 error_code = 0; 00725 bEE_RWsuccess = true; 00726 error_code += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00727 00728 // send read command 00729 chCMD = bma180_cmd::ADDRESS_VER | bma180_cmd::FLAG_R; 00730 error_code += sub_spi_transfer( handle_sub20, &chCMD, 0, 1, SS_CONF(chip_select,SS_L) ); 00731 error_code += sub_spi_transfer( handle_sub20, 0, &chCHIP_ID, 1, SS_CONF(chip_select,SS_L) ); 00732 error_code += sub_spi_transfer( handle_sub20, 0, &chALML_VER, 1, SS_CONF(chip_select,SS_L) ); 00733 00734 // ensure CS is high 00735 error_code += sub_spi_transfer( handle_sub20, 0, &chCMD, 1, SS_CONF(chip_select,SS_H) ); 00736 00737 // Verify if a BMA180 is connected on the respective ChipSelect 00738 if( error_code == 0 && ( 0 < (unsigned short) chCHIP_ID) && ( 0 < (unsigned short)chALML_VER) ) 00739 { 00740 if( !bWriteEEPROM == true) 00741 { 00742 // Write X axis offset 00743 chMSB = (char)( (uiBiasX&0xFF0) >> 4 ); 00744 chLSB = (char)( (uiBiasX&0x0F) ); 00745 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::ADDRESS_OFFSET_X, 0, 8, chMSB, chip_select, handle_sub20 ); 00746 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::ADDRESS_OFFSET_LSB1, 4, 4, chLSB, chip_select, handle_sub20 ); 00747 00748 // Write Y axis offset 00749 chMSB = (char)( (uiBiasY&0xFF0) >> 4 ); 00750 chLSB = (char)( (uiBiasY&0x0F)); 00751 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::ADDRESS_OFFSET_Y, 0, 8, chMSB, chip_select, handle_sub20 ); 00752 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::ADDRESS_OFFSET_LSB2, 0, 4, chLSB, chip_select, handle_sub20 ); 00753 00754 // Write Z axis offset 00755 chMSB = (char)( (uiBiasZ&0xFF0) >> 4 ); 00756 chLSB = (char)( (uiBiasZ&0x0F) ); 00757 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::ADDRESS_OFFSET_Z, 0, 8, chMSB, chip_select, handle_sub20 ); 00758 bEE_RWsuccess &= write_bit_eeprom_sub20( bma180_cmd::ADDRESS_OFFSET_LSB2, 4, 4, chLSB, chip_select, handle_sub20 ); 00759 00760 if( bEE_RWsuccess ) 00761 { 00762 std::cout << "Writing to image " << std::endl; 00763 bSuccess = true; 00764 } 00765 else 00766 { 00767 bSuccess = false; 00768 ROS_WARN("Cannot write BMA180 image.\n"); 00769 } 00770 } 00771 else 00772 { 00773 // Writing to the EEPROM is done by indirect write, i.e. setting values to image register 00774 // and then writing to the eeprom, which in fact reads the image register 00775 // Per write 16 bit from image to eeprom are written and only even addresses can used (see docu) 00776 bEE_RWsuccess &= write_bit_eeprom_sub20(bma180_cmd::ADDRESS_EE_GAIN_Z, 0, 8, 0x00, chip_select, handle_sub20 ); 00777 bEE_RWsuccess &= write_bit_eeprom_sub20(bma180_cmd::ADDRESS_EE_OFFSET_LSB2, 0, 8, 0x00, chip_select, handle_sub20 ); 00778 bEE_RWsuccess &= write_bit_eeprom_sub20(bma180_cmd::ADDRESS_EE_OFFSET_X, 0, 8, 0x00, chip_select, handle_sub20 ); 00779 bEE_RWsuccess &= write_bit_eeprom_sub20(bma180_cmd::ADDRESS_EE_OFFSET_Z, 0, 8, 0x00, chip_select, handle_sub20 ); 00780 00781 if( bEE_RWsuccess ) 00782 { 00783 ROS_INFO("BMA180 EEPROM written.\n"); 00784 bSuccess = true; 00785 } 00786 else 00787 { 00788 bSuccess = false; 00789 } 00790 } 00791 } 00792 else 00793 { 00794 // unsuccessful operation 00795 bSuccess = false; 00796 } 00797 return bSuccess; 00798 }; 00799 00800 00801 void Bma180::set_calibstatus( bool bCalibrate) 00802 { 00803 if( bCalibrate == true ) 00804 { 00805 std::string myAnswer; 00806 std::cout << "Sensors shall be calibrated <Y/N>? "; 00807 std::getline( std::cin, myAnswer ); 00808 if( (0 == myAnswer.find('Y')) || (0 == myAnswer.find('y')) ) 00809 { 00810 unsigned short myCS; 00811 std::cout << "Specify ChipSelect <0..4>? "; 00812 if( std::cin >> myCS ) 00813 { 00814 if( myCS < bma180_cmd::MAX_NUM_SENSORS ) 00815 { 00816 bExecuteCalibration = true; 00817 bCalibrationCompleted = false; 00818 iCalib_CS = myCS; 00819 } 00820 else 00821 { 00822 bExecuteCalibration = false; 00823 bCalibrationCompleted = true; 00824 } 00825 } 00826 else 00827 { 00828 bExecuteCalibration = false; 00829 bCalibrationCompleted = true; 00830 std::cin.clear(); 00831 } 00832 } 00833 else 00834 { 00835 bExecuteCalibration = false; 00836 bCalibrationCompleted = true; 00837 } 00838 } 00839 else 00840 { 00841 bExecuteCalibration = false; 00842 bCalibrationCompleted = true; 00843 } 00844 }; 00845 00846 00847 00848 00849 // main loop 00850 00851 int main(int argc, char **argv) 00852 { 00853 int count = 1; 00854 int i = 0; 00855 00856 00857 // Parameter Server values 00858 double max_acceleration_g, dRate_Hz, dBandwidth_Hz; 00859 bool bCalibrate; 00860 std::string sSub20Serial; 00861 00862 // Set initialization values 00863 max_acceleration_g = 2.0; 00864 dBandwidth_Hz = 100; 00865 dRate_Hz = 100; 00866 bCalibrate = false; 00867 sSub20Serial = "0651"; 00868 00869 Bma180 bma180_attached( max_acceleration_g, dBandwidth_Hz, bCalibrate, dRate_Hz, sSub20Serial ); 00870 OneBma180Meas sOneMeas; 00871 bma180::bma180meas msg; 00872 std::list<OneBma180Meas> measurements_list; 00873 00874 00875 // Run sensor node 00876 // some sort of rate setup here 00877 while( true ) 00878 { 00879 // initiate a measurement 00880 try 00881 { 00882 bma180_attached.GetMeasurements(measurements_list); 00883 } 00884 00885 catch( std::string e ) 00886 { 00887 ROS_ERROR( "An exception occurred: %s\n", e.c_str() ); 00888 std::exit(1); 00889 } 00890 00891 while( !measurements_list.empty() ) 00892 { 00893 sOneMeas = measurements_list.back(); 00894 measurements_list.pop_back(); 00895 00896 // only publish if a successful measurement was received 00897 if( sOneMeas.bMeasAvailable == true ) 00898 { 00899 msg.strIdSubDev = sOneMeas.serial_number; 00900 00901 // Print results to screen 00902 for( i = 0; i < sOneMeas.iNumAccels; i++ ) 00903 { 00904 printf("BMA180 %d\tx: %1.4f\ty: %1.4f\tz: %1.4f\n", sOneMeas.chip_select[i], sOneMeas.dAccX[i], sOneMeas.dAccY[i], sOneMeas.dAccZ[i] ); 00905 } 00906 } 00907 } 00908 00909 //loop_rate.sleep(); 00910 usleep( 1e6 / dRate_Hz ); 00911 00912 ++count; 00913 } 00914 } 00915 00916