bmc050.hpp
Go to the documentation of this file.
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 #ifndef BMC050_H_
00051 #define BMC050_H_
00052 
00053 #include <cmath>
00054 #include <unistd.h> // for the sleep function
00055 #include <iostream> // for the calibration routine
00056 
00057 // ROS debugging output
00058 #include <ros/console.h>
00059 
00060 #include <bosch_drivers_sensor_driver.hpp>
00061 #include <bosch_drivers_hardware_interface.hpp>
00062 
00063 #include "bmc050_parameters.hpp"
00064 
00065 using namespace bosch_drivers_common;
00066 
00083 class BMC050: public sensor_driver, public BMC050Parameters
00084 {
00085 
00086 public:
00087  
00088  /*----- Bit Flags --------------------------------------------------- */
00089  // class copies of the sensor registers, so not to overwrite data 
00099   uint8_t modechange_accel_;         
00100   uint8_t softreset_;            
00101   uint8_t rate_compass_;       
00102   uint8_t set_filter_;    
00103  
00104   // POWERFLAGS
00105   static const uint8_t SUSPEND     = 0x07; // b7  
00106   static const uint8_t LOWPOWER_EN = 0x06; // b6
00107   static const uint8_t SLEEP_DUR   = 0x01; // b1 is the lsb
00108  
00109   // changing modes
00110   static const uint8_t SET_OPMODE_SLEEP  = 0x03;
00111   static const uint8_t SET_OPMODE_FORCED = 0x01;
00112   static const uint8_t OPMODE            = 0x01; // (b1 is the lsb)  
00113   static const uint8_t POWER_CONTROL_BIT = 0x00;
00114 
00115   // Specific commands
00116   static const uint8_t SOFTRESET_COMPASS_CMD = 0x82;
00117   static const uint8_t SOFTRESET_ACCEL_CMD   = 0xB6;
00118   static const uint8_t FLAG_R                = 0x80; // for SPI reads
00119 
00120   // BitFlags: BANDWIDTH REG
00121   static const uint8_t DATA_HIGH_BW = 7; // <7>
00122   // BitFlags: RATE_COMPASS
00123   static const uint8_t Data_Rate    = 3; // <5:3> in 0x4C
00124  
00125   // BitFlags: ADDRESS_ENABLE_CALIBRATION
00126   static const uint8_t hp_z_en = 2;
00127   static const uint8_t hp_y_en = 1;
00128   static const uint8_t hp_x_en = 0;
00129 
00130   // BitFlags: ADDRESS_OFFSET_TARGET register:
00131   static const uint8_t offset_target_x = 1; // <2:1>
00132   static const uint8_t offset_target_y = 3; // <4:3>
00133   static const uint8_t offset_target_z = 5; // <6:5>
00134 
00135   enum compass_mode
00136   {
00137     compass_suspend_,
00138     compass_sleep_,
00139     compass_normal_,
00140     compass_forced_
00141   };
00142 
00143   enum accel_mode
00144   {
00145     accel_suspend_,
00146     accel_normal_,
00147     accel_low_power_
00148   };
00149 
00150   // Constructor
00155   BMC050( bosch_hardware_interface* hw );
00156 
00157   // Destructor
00158   ~BMC050();
00168   uint8_t getDeviceAddress(); 
00169 
00176   bool initialize();
00177 
00185   bool readRegistersAccel();
00186 
00194   bool readRegistersCompass();
00195 
00201   bool takeMeasurement();
00202 
00210   bool softResetAccel();
00211 
00222   bool changeAccelRange();         
00223  
00235   bool filterData( bool request );    
00236 
00247   bool changeAccelBandwidth();       
00248 
00256   bool getAccelData();
00257   
00267   double getAccelX();
00268 
00278   double getAccelY();
00279 
00288   double getAccelZ();
00289 
00298   double getTemperature();
00299 
00311   void simpleCalibrationAccel();
00312 
00313   // Compass: settings
00324   bool softResetCompass();
00325 
00336   bool changeCompassRate(); 
00337 
00344   bool changeNumRepetitionsXY();
00345 
00352   bool   changeNumRepetitionsZ();
00353  
00354   // Compass: data
00361   bool    getCompassData();
00362 
00363   double   getCompassX();
00364   double   getCompassY();
00365   double   getCompassZ();
00366   uint16_t  getRHall();
00367  
00374   double getUncompensatedYaw();
00375  
00376   // Modes and Settings (Power Management, Overall Behavior)
00377   bool enterLowPowerModeAccel();      //|
00378   bool enterSuspendModeAccel();       //|--> not yet implemented.
00379   bool enterNormalModeAccel();       //|
00380   //bool setBandwidth(accel_bandwidth bw); //|
00381 
00382   bool enterSuspendModeCompass(); 
00383   bool enterSleepModeCompass(); 
00384   bool enterNormalModeCompass();  
00385   bool enterForcedModeCompass();
00386 
00387   bool readRegAccel( uint8_t reg, uint8_t* value );                
00388   bool readRegCompass( uint8_t reg, uint8_t* value );                 
00389   bool writeToAccelReg( uint8_t reg, uint8_t value );
00390   bool writeToCompassReg( uint8_t reg, uint8_t value );
00391   bool writeToCompassRegAndVerify( uint8_t reg, uint8_t value, uint8_t expected );
00392   bool writeToAccelRegAndVerify( uint8_t reg, uint8_t value, uint8_t expected );
00393   bool printOffsets();
00394 
00395 //private:
00396   // Data Registers
00397   static const uint8_t ADDRESS_ACCLXYZ   = 0x02;
00398   static const uint8_t ADDRESS_ACC_X_LSB = 0x02;
00399   static const uint8_t ADDRESS_ACC_X_MSB = 0x03;
00400   static const uint8_t ADDRESS_ACC_Y_LSB = 0x04;
00401   static const uint8_t ADDRESS_ACC_Y_MSB = 0x05;
00402   static const uint8_t ADDRESS_ACC_Z_LSB = 0x06;
00403   static const uint8_t ADDRESS_ACC_Z_MSB = 0x07;
00404  
00405   static const uint8_t ADDRESS_TEMPERATURE = 0x08;
00406  
00407   static const uint8_t ADDRESS_ENABLE_CALIBRATION = 0x36;
00408   static const uint8_t ADDRESS_OFFSET_TARGET      = 0x37;
00409   static const uint8_t OFFSET_FILT_X              = 0x38;
00410   static const uint8_t OFFSET_UNFILT_Z            = 0x3D;
00411  
00412   static const uint8_t ADDRESS_COMPASS_XYZ   = 0x42;
00413   static const uint8_t ADDRESS_COMPASS_X_LSB = 0x42;
00414   static const uint8_t ADDRESS_COMPASS_X_MSB = 0x43;
00415   static const uint8_t ADDRESS_COMPASS_Y_LSB = 0x44;
00416   static const uint8_t ADDRESS_COMPASS_Y_MSB = 0x45;
00417   static const uint8_t ADDRESS_COMPASS_Z_LSB = 0x46;
00418   static const uint8_t ADDRESS_COMPASS_Z_MSB = 0x47;
00419  
00420   static const uint8_t ADDRESS_RHALL     = 0x48;
00421   static const uint8_t ADDRESS_RHALL_LSB = 0x48;
00422   static const uint8_t ADDRESS_RHALL_MSB = 0x49;
00423  
00424   static const uint8_t ADDRESS_COMPASS_REPZ  = 0x51;
00425   static const uint8_t ADDRESS_COMPASS_REPXY = 0x52;
00426  
00427   static const uint8_t ADDRESS_ACCEL_RANGE   = 0x0F;
00428 
00429   // Settings Registers
00430   // Accel
00431   static const uint8_t MODECHANGE_ACCEL = 0x11;
00432   static const uint8_t SOFTRESET_ACCEL  = 0x14;
00433   static const uint8_t BANDWIDTH_REG    = 0x10;
00434   static const uint8_t SET_FILTER       = 0x13;
00435   // Compass
00436   static const uint8_t RATE_COMPASS     = 0x4C;
00437   static const uint8_t SOFTRESET_COMPASS_REG = 0x4B;
00438 
00439 
00440   uint8_t RawData[13]; 
00441 
00442   double  AccelX_;
00443   double  AccelY_;
00444   double  AccelZ_;
00445   double  Temperature_;
00446   double  StaticPitch_;
00447   double  StaticRoll_;  
00448   
00449   double CompassX_;
00450   double CompassY_;
00451   double CompassZ_;
00452   uint16_t RHall_;
00453   
00454   double SensitivityXY_;
00455   double SensitivityZ_;
00456   double TempSlope_;
00457   
00458   compass_mode compass_mode_;
00459   accel_mode accel_mode_;
00460   bandwidth prev_bw_reg_;   // most recently written bandwidth
00461 };
00462 
00463 #endif // BMC050_H_
00464 


bmc050_driver
Author(s): Joshua Vasquez, Philip Roan. Maintained by Philip Roan
autogenerated on Sat Dec 28 2013 16:48:51