00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2012, Robert Bosch LLC. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Robert Bosch nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 *********************************************************************/ 00036 00037 /********************************************************************* 00038 * 00039 * Disclaimer 00040 * 00041 * This source code is not officially released or supported by Bosch Sensortec. 00042 * Please contact the listed authors with bugs or other modifications. 00043 * If you would like the official Bosch Sensortec drivers, please contact: 00044 * contact@bosch-sensortec.com 00045 * 00046 *********************************************************************/ 00047 00048 //\Author Joshua Vasquez and Philip Roan, Robert Bosch LLC 00049 00050 #include "bmc050_driver/bmc050_parameters.hpp" 00051 00052 BMC050Parameters::BMC050Parameters() : 00053 accel_sensitivity_( 0.00391 ), // units: [g/LSB] // corresponds to RANGE_2 00054 repsXY_( 0 ), 00055 repsZ_( 0 ) 00056 { 00057 setFrequency( 400000 ); 00058 this->setProtocol( I2C ); 00059 00060 // clear flags: 00061 flags_ = 0; 00062 this->setSpiMode( SPI_MODE_0 ); 00063 this->setByteOrder( MSB_FIRST ); 00064 this->setAccelPin( 0 ); 00065 this->setCompassPin( 1 ); 00066 00067 // default Accel settings: 00068 this->setAccelRange( RANGE_2 ); 00069 this->setAccelBandwidth( BW_1000HZ ); 00070 this->setFilter( true ); // default: filter accel data. 00071 00072 // default Compass settings: 00073 this->setCompassRate( ODR_10HZ ); // default: output compass rate is 10 Hz. 00074 00075 // these parameters can be adjusted if other settings are desired: 00076 this->setCSB2( 0 ); 00077 this->setSDO( 0 ); 00078 } 00079 00080 00081 BMC050Parameters::~BMC050Parameters() // Destructor 00082 { 00083 } 00084 00085 00086 double BMC050Parameters::getAccelSensitivity() 00087 { 00088 return accel_sensitivity_; 00089 } 00090 00091 00092 uint8_t BMC050Parameters::getAccelAddress() 00093 { 00094 // depends on the protocol: 00095 switch( protocol_ ) 00096 { 00097 case I2C: 00098 // depends on BOTH SDO and CSB2 pins 00099 if ( (CSB2 == 0) && (SDO == 0) ) 00100 return 0x18; 00101 else if ( (CSB2 == 0) && (SDO == 1) ) 00102 return 0x19; 00103 else if ( (CSB2 == 1) && (SDO == 0) ) 00104 return 0x18; 00105 else 00106 return 0x19; 00107 case SPI: 00108 flags_ = ((0x0F)&flags_) | (accel_pin_ << 4); // spi flags must be adjusted every time we wish to talk to a different sensor on the BMC050 00109 return accel_pin_; 00110 default: 00111 ROS_ERROR("BMC050Parameters::getAccelAddress(): invalid protocol."); 00112 return 0; 00113 } 00114 } 00115 00116 00117 uint8_t BMC050Parameters::getCompassAddress() 00118 { 00119 // depends on the protocol: 00120 switch( protocol_ ) 00121 { 00122 case I2C: 00123 // depends on BOTH SDO and CSB2 pins 00124 if ( (CSB2 == 0) && (SDO == 0) ) 00125 return 0x10; 00126 else if ( (CSB2 == 0) && (SDO == 1) ) 00127 return 0x11; 00128 else if ( (CSB2 == 1) && (SDO == 0) ) 00129 return 0x12; 00130 else 00131 return 0x13; 00132 case SPI: 00133 flags_ = ((0x0F)&flags_) | (compass_pin_ << 4); // spi flags must be adjusted every time we wish to talk to a different sensor on the BMC050 00134 return compass_pin_; 00135 default: 00136 ROS_ERROR("BMC050Parameters::getCompassAddress(): invalid protocol."); 00137 return 0; 00138 } 00139 } 00140 00141 00142 bool BMC050Parameters::setProtocol( interface_protocol protocol ) 00143 { 00144 switch( protocol ) 00145 { 00146 case I2C: 00147 protocol_ = protocol; 00148 break; 00149 case SPI: 00150 protocol_ = protocol; 00151 break; 00152 default: 00153 ROS_ERROR("bma180_parameters:Unsupported protocol."); 00154 return false; 00155 } 00156 return true; 00157 } 00158 00159 00160 bool BMC050Parameters::setFrequency( int frequency ) 00161 { 00162 frequency_ = frequency; 00163 return true; 00164 } 00165 00166 00167 int BMC050Parameters::getFrequency() 00168 { 00169 return frequency_; 00170 } 00171 00172 00173 interface_protocol BMC050Parameters::getProtocol() 00174 { 00175 return protocol_; 00176 } 00177 00178 00179 bool BMC050Parameters::setPin( uint8_t pin ) 00180 { 00181 // adjust pin to desired value: 00182 pin_ = pin; 00183 // adjust the current flags to include the pin value: 00184 flags_ = ((0x0F)&flags_) | (pin_ << 4); 00185 00186 return true; 00187 } 00188 00189 00190 bool BMC050Parameters::setAccelPin( uint8_t pin ) 00191 { 00192 if( pin < 16 ) // pin value must fit in 4 bits of uint8_t flags 00193 { 00194 accel_pin_ = pin; 00195 return true; 00196 } 00197 else 00198 return false; 00199 } 00200 00201 00202 bool BMC050Parameters::setCompassPin( uint8_t pin ) 00203 { 00204 if( pin < 16 ) // pin value must fit in 4 bits of uint8_t flags 00205 { 00206 compass_pin_ = pin; 00207 return true; 00208 } 00209 else 00210 return false; 00211 } 00212 00213 00214 int BMC050Parameters::getPin() // irrelevant 00215 { 00216 return pin_; 00217 } 00218 00219 int* BMC050Parameters::getFlags() 00220 { 00221 return &flags_; 00222 } 00223 00224 00225 bool BMC050Parameters::setSpiMode( uint8_t mode ) 00226 { 00227 switch( mode ) 00228 { 00229 case SPI_MODE_3: 00230 break; 00231 case SPI_MODE_0: 00232 break; 00233 case SPI_MODE_1: {} 00234 case SPI_MODE_2: {} 00235 default: 00236 ROS_ERROR("bma180_parameters: SPI_MODE can only be one of four choices"); 00237 return false; 00238 00239 } 00240 // adjust the flags 00241 flags_ = ((0xFC & flags_) | (mode) ); 00242 return true; 00243 } 00244 00245 00246 bool BMC050Parameters::setByteOrder( uint8_t value ) 00247 { 00248 if( value > 1 ) 00249 { 00250 ROS_ERROR("bma180_parameters: Byte order must be either LSBFIRST or MSBFIRST"); 00251 return false; 00252 } 00253 // adjust the flags 00254 flags_ = ((0xFB & flags_) | (value << 2)); 00255 return true; 00256 } 00257 00258 00259 void BMC050Parameters::setCSB2( bool val ) 00260 { 00261 CSB2 = val; 00262 } 00263 00264 00265 void BMC050Parameters::setSDO( bool val ) 00266 { 00267 SDO = val; 00268 } 00269 00270 00271 void BMC050Parameters::setAccelRange( accel_range new_range ) 00272 { 00273 accel_range_ = new_range; 00274 } 00275 00276 00277 BMC050Parameters::accel_range BMC050Parameters::getAccelRange() 00278 { 00279 return accel_range_; 00280 } 00281 00282 00283 void BMC050Parameters::setFilter( bool request ) 00284 { 00285 accel_is_filtered_ = request; 00286 } 00287 00288 00289 void BMC050Parameters::setAccelBandwidth( bandwidth bw ) 00290 { 00291 bw_reg_ = bw; 00292 } 00293 00294 00295 void BMC050Parameters::setCompassRate( compass_rate rate ) 00296 { 00297 compass_rate_ = rate; 00298 } 00299 00300 00301 void BMC050Parameters::setNumRepetitionsXY( uint16_t num_reps ) 00302 { 00303 uint16_t actual_reps = num_reps; 00304 00305 // check if even: 00306 if( num_reps %2 == 0 ) 00307 { 00308 ROS_WARN("BMC050Parameters::setNumRepetitionsXY(): Only odd numbers are valid. Value converted to an odd number.."); 00309 // make odd: 00310 actual_reps = num_reps + 1; 00311 } 00312 00313 // only odd numbers from 1 through 511 are valid 00314 if( num_reps > 511 ) 00315 { 00316 actual_reps = 511; 00317 ROS_WARN("BMC050Parameters::setNumRepetitionsXY(): Repetititions must be less than 512"); 00318 } 00319 else 00320 { 00321 if( num_reps == 0 ) 00322 { 00323 actual_reps = 1; 00324 ROS_WARN("BMC050Parameters::setNumRepetitionsXY(): Repetitions must be greater than zero."); 00325 } 00326 } 00327 // construct hex code: 00328 actual_reps = (uint8_t)( (actual_reps - 1) / 2); // see datasheet page 78 00329 00330 // store to class variable: 00331 repsXY_ = actual_reps; 00332 00333 ROS_INFO("BMC050Parameters::setNumRepetitionsXY(): input: %d actual: %d", num_reps, actual_reps); 00334 } 00335 00336 00337 void BMC050Parameters::setNumRepetitionsZ( uint16_t num_reps ) 00338 { 00339 uint16_t actual_reps = num_reps; 00340 00341 // only integers from 1 through 256 are valid: 00342 if( num_reps > 256 ) 00343 { 00344 actual_reps = 256; 00345 ROS_WARN("BMC050Parameters::setNumRepetitionsXY(): Repetititions must be less than 256"); 00346 } 00347 else 00348 { 00349 if( num_reps == 0 ) 00350 { 00351 actual_reps = 1; 00352 ROS_WARN("BMC050Parameters::setNumRepetitionsXY(): Repetitions must be greater than zero."); 00353 } 00354 } 00355 // construct hex code and store to class variable: 00356 repsZ_ = (uint8_t)(actual_reps - 1); // see datasheet pg 78 00357 00358 ROS_INFO("BMC050Parameters::setNumRepetitionsZ(): input: %d actual: %d", num_reps, actual_reps); 00359 }