bmg160.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, Philip Roan, Bosch LLC
00049 
00050 #ifndef BMG160_H_
00051 #define BMG160_H_
00052 
00053 #include <iostream> // for the calibration routine
00054 #include <cmath>
00055 #include <unistd.h> // for the sleep function
00056 
00057 // ROS header for output
00058 #include <ros/console.h>
00059 
00060 #include <bosch_drivers_sensor_driver.hpp>
00061 #include <bosch_drivers_hardware_interface.hpp>
00062 #include "bmg160_parameters.hpp"
00063 
00064 #include <bmg160_driver/bmg160meas.h>
00065 
00066 using namespace bosch_drivers_common;
00067 
00082 class BMG160: public sensor_driver, public BMG160Parameters
00083 {
00084  
00085 public:
00086   
00088   static const uint8_t SOFTRESET_CMD = 0xB6;
00089 
00096   static const uint8_t DATA_HIGH_BW = 7;  // <7>
00097   
00104   static const uint8_t fast_offset_en   = 3;
00105   static const uint8_t fast_offset_en_z = 2;
00106   static const uint8_t fast_offset_en_y = 1;
00107   static const uint8_t fast_offset_en_x = 0;
00108   
00115   static const uint8_t fast_offset_unfilt  = 7;
00116 
00123   static const uint8_t slow_offset_th   = 6; // <7:6>
00124   static const uint8_t slow_offset_dur  = 3; // <5:3>
00125   static const uint8_t slow_offset_en_x = 0;
00126   static const uint8_t slow_offset_en_y = 1;
00127   static const uint8_t slow_offset_en_z = 2;
00128 
00135   static const uint8_t slow_offset_unfilt = 5;
00136   
00143   static const uint8_t nvm_load = 3;
00144 
00145   BMG160( bosch_hardware_interface* hw );
00146   ~BMG160();
00147 
00156   uint8_t getDeviceAddress(); 
00157   
00164   bool initialize();
00165 
00173   bool takeMeasurement();
00174 
00182   bool softReset();
00183 
00194   bool changeRange();                  
00195 
00208   bool filterData( bool request );         
00209   
00224   bool changeBandwidth();  
00225 
00235   double    getGyroX();
00236 
00246   double getGyroY();
00247 
00257   double getGyroZ();
00258 
00268   double getTemperature();
00269 
00281   void SimpleCalibration();
00282 
00289   bool readSensorData( uint8_t reg, uint8_t* data, uint8_t num_bytes );
00290 
00298   void computeOffsets( uint8_t* raw_offset_data, int16_t* clean_offset_data );
00299 
00306   bool printOffsets();
00307 
00308 
00310   
00314   static const uint8_t SLAVE_ADDRESS0           = 0x68;
00318   static const uint8_t SLAVE_ADDRESS1            = 0x69;
00319   
00320   static const uint8_t ADDRESS_GYRO_X_LSB        = 0x02;
00321   static const uint8_t ADDRESS_GYRO_Y_LSB        = 0x04;
00322   static const uint8_t ADDRESS_GYRO_Z_LSB        = 0x06;
00323   static const uint8_t ADDRESS_TEMPERATURE       = 0x08;
00324   
00325   static const uint8_t ADDRESS_RANGE             = 0x0F;
00326   static const uint8_t ADDRESS_BANDWIDTH         = 0x10;
00327   static const uint8_t ADDRESS_FILTER            = 0x13;
00328   static const uint8_t ADDRESS_SOFTRESET         = 0x14;
00329   static const uint8_t ADDRESS_FILTERED_CAL      = 0x1A;
00330   static const uint8_t ADDRESS_FILTERED_CAL_FAST = 0x1B;
00331   static const uint8_t ADDRESS_ENABLE_CAL        = 0x31;
00332   static const uint8_t ADDRESS_ENABLE_FAST_CAL  = 0x32;
00333   static const uint8_t ADDRESS_NVM            = 0x33;
00334 
00346   static const uint8_t ADDRESS_OFFSETS          = 0x36; 
00347 
00348   double GyroX_;
00349   double GyroY_;
00350   double GyroZ_; 
00351   double Temperature_;  
00352   double TempSlope_;
00353   
00354 private:
00355   bool readReg( uint8_t reg, uint8_t* value );
00356   bool writeToReg( uint8_t reg, uint8_t value );
00357   bool writeToRegAndVerify( uint8_t reg, uint8_t value, uint8_t expected );
00358 };
00359 
00360 #endif // BMC050_H_


bmg160_driver
Author(s): Joshua Vasquez, Philip Roan. Maintained by Philip Roan
autogenerated on Mon Oct 6 2014 10:10:13