smi540.h
Go to the documentation of this file.
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  * smi540.h
00032  *
00033  *  Created on: Jul 27, 2011
00034  *      Author: Lucas Marti, Robert Bosch LLC |
00035  *      Author: Nikhil Deshpande, Robert Bosch LLC |
00036  */
00037 
00038 #ifndef SMI540_H_
00039 #define SMI540_H_
00040 
00041 #include "smi540/smi540meas.h"
00042 #include <list>
00043 #include <libsub.h> // sub20 device
00044 
00045 //Define SMI540 specifics
00046 namespace smi540_cmd
00047 {
00048   //Define MM5 commands
00049   static char chRD_ACT_DATA_64[4] = { 0x41, 0x99, 0x00, 0x5C };
00050   static char chTRIGGER_RESET[4]  = { 0x61, 0x03, 0x00, 0xE9 };
00051   static char chRD_STATUS_A[4]  = { 0x40, 0x35, 0x00, 0x4F };
00052 
00053   //Specify MM5 Scale Factor - note: Pos is slightly different from negative
00054   const double fSFACC_inv = 6667;
00055   const double fSFGYRO_inv = 175;
00056 
00057   //Define enumerated sensor type
00058   enum eSensorType { eACCEL, eGYRO };
00059 
00060   //Define default sampling rate
00061   const double DEFAULT_RATE_Hz = 20;
00062   const std::string sSUB20SERIAL("064E");
00063   const unsigned short MAX_SENSORS = 5;          //Defined by the Xdimax Unit (which supports 5 sensors per box)
00064   const unsigned short uSERIALNUMLENGTH   = 20;
00065 }
00066 
00067 //Define measurement output
00068 struct OneSmi540Meas
00069 {
00070   bool        bMeasAvailable; //indicates true if a valid measurement is available
00071   int         iNumAccels;
00072   double      dRateZ[smi540_cmd::MAX_SENSORS];
00073   double      dAccX[smi540_cmd::MAX_SENSORS];
00074   double      dAccY[smi540_cmd::MAX_SENSORS];
00075   ros::Time   dtomeas; //time tag measurement immediately in case of other delays
00076   std::string strSerial;
00077   int         iChipSelect[smi540_cmd::MAX_SENSORS];
00078 };
00079 
00080 
00082 
00087 class Smi540
00088 {
00089 public:
00091 
00099   Smi540(std::string);
00100 
00102 
00106   virtual ~Smi540();
00107 
00109 
00119   void GetMeasurements( std::list<OneSmi540Meas>& );
00120 
00121 private:
00122   // structure for one smi540 configuration
00123   struct OneSmi540Config
00124   {
00125     bool bConfigured;
00126   };
00127   // structure for one Sub20 device configuration
00128   struct OneSub20Config
00129   {
00130     std::string     strSub20Serial;
00131     sub_handle      handle_subdev;
00132     sub_device      subdev;
00133     bool            bSubSPIConfigured;
00134     OneSmi540Config Smi540Cluster[smi540_cmd::MAX_SENSORS];
00135   };
00136   std::list<OneSub20Config>   Sub20Device_list;
00137 
00138   //subdevice handle for closing the device in destructor
00139   sub_handle subhndl;
00140   //status flag indicating if subdevice has been opened
00141   bool bSubDeviceOpen;
00142   //status flag indicating if SPI configuration for SMI530/540 has been stored
00143   bool bSubDeviceConfigured;
00144   //Serial number of subdevice
00145   std::string strSerial;
00147   double mm5data_to_double( char, char, smi540_cmd::eSensorType );
00149   void confsens_on_sub20( OneSub20Config* );
00150 };
00151 
00152 
00153 #endif /* SMI540_H_ */
00154 


smi540
Author(s): Lukas Marti, Nikhil Deshpande (Maintained by Philip Roan)
autogenerated on Sat Dec 28 2013 16:49:36