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 /* 00051 * This class contains a set of parameters that are specific to the 00052 * BMC050 sensor. The class inherits from a generic parent class of 00053 * parameters. I have listed the inherited parameters as comments 00054 * below. 00055 * The sensor parameters are stored as members of the class and 00056 * accessible to other classes through methods such as 00057 * "getProtocol()." 00058 */ 00059 00060 #ifndef BMC050_PARAMETERS_H_ 00061 #define BMC050_PARAMETERS_H_ 00062 00063 // ROS debugging output 00064 #include <ros/console.h> 00065 00066 #include <bosch_drivers_parameters.hpp> 00067 #include <bosch_drivers_hardware_interface.hpp> 00068 00069 using namespace bosch_drivers_common; 00070 00071 class BMC050Parameters: public Parameters 00072 { 00073 public: 00074 friend class BMC050; 00075 00076 enum accel_range 00077 { 00078 RANGE_2 = 0x03, // ±2.0 g 3.91 [mg/LSB] 00079 RANGE_4 = 0x05, // ±4 g 7.81 [mg/LSB] 00080 RANGE_8 = 0x08, // ±8 g 15.62 [mg/LSB] 00081 RANGE_16 = 0x0C // ±16 g 31.25 [mg/LSB] 00082 }; 00083 00084 enum bandwidth 00085 { 00086 BW_8HZ = 0x08, // 7.81 [Hz] 00087 BW_16HZ = 0x09, // 15.63 [Hz] 00088 BW_31HZ = 0x0A, // 31.25 [Hz] 00089 BW_63HZ = 0x0B, // 62.5 [Hz] 00090 BW_125HZ = 0x0C, // 125 [Hz] 00091 BW_250HZ = 0x0D, // 250 [Hz] 00092 BW_500HZ = 0x0E, // 500 [Hz] 00093 BW_1000HZ = 0x0F // 1000 [Hz] 00094 }; 00095 00096 00097 // Compass Output Data Rate: 00098 // write to 0x4C 00099 enum compass_rate 00100 { 00101 ODR_10HZ = 0x00, // 000b default 00102 ODR_2HZ = 0x01, // 001b 00103 ODR_6HZ = 0x02, // 010b 00104 ODR_8HZ = 0x03, // 011b 00105 ODR_15HZ = 0x04, // 100b 00106 ODR_20HZ = 0x05, // 101b 00107 ODR_25HZ = 0x06, // 110b 00108 ODR_30HZ = 0x07 // 111b 00109 }; 00110 00114 BMC050Parameters(); 00115 00119 ~BMC050Parameters(); 00120 00127 bool setProtocol( interface_protocol protocol ); 00128 00129 00137 bool setFrequency( int frequency ); 00138 00148 bool setPin( uint8_t pin ); // always false... Needed because of inheritance 00149 00157 bool setAccelPin( uint8_t pin ); 00158 00164 bool setCompassPin( uint8_t pin ); 00165 00167 00174 void setAccelRange( accel_range new_range ); 00175 00184 void setFilter(bool input); 00185 00194 void setAccelBandwidth( bandwidth bw ); // sets bandwidth register according to desired bandwidth 00195 00196 // compass-specific 00204 void setCompassRate( compass_rate rate ); 00205 00213 void setNumRepetitionsXY( uint16_t num_repetitions ); 00214 00221 void setNumRepetitionsZ( uint16_t num_repetitions ); 00222 00223 // These pins determine Accel and Compass addresses: 00234 void setCSB2( bool val ); 00235 00246 void setSDO( bool val ); 00247 00254 accel_range getAccelRange(); 00255 00256 // FIXME: change level of access on these methods: 00257 uint8_t getAccelAddress(); // return the i2c addresses based on 00258 uint8_t getCompassAddress(); // settings in the two previous methods. 00259 00268 double getAccelSensitivity(); 00269 00270 interface_protocol getProtocol(); 00271 int getFrequency(); 00272 int* getFlags(); 00273 int getPin(); // valid for SPI only 00274 00275 00276 private: 00277 accel_range accel_range_; 00278 bool accel_is_filtered_; 00279 double accel_sensitivity_; 00280 bandwidth bw_reg_; 00281 compass_rate compass_rate_; 00282 uint8_t repsXY_; 00283 uint8_t repsZ_; 00284 00285 bool CSB2; 00286 bool SDO; 00287 uint8_t accel_pin_; 00288 uint8_t compass_pin_; 00289 00303 bool setSpiMode( uint8_t mode ); 00304 00316 bool setByteOrder( uint8_t value ); // MSB_FIRST or LSB_FIRST 00317 00318 }; 00319 00320 #endif // BMC050_PARAMETERS_H_