Contains added code for stm32-L432KC compatibility

Dependents:   BNO080_stm32_compatible

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers BNO080.h Source File

BNO080.h

00001 /*
00002  * This is USC RPL's ARM MBed BNO080 IMU driver, by Jamie Smith.
00003  *
00004  * It is based on SparkFun and Nathan Seidle's Arduino driver for this chip, but is substantially rewritten and adapted.
00005  * It also supports some extra features, such as setting the mounting orientation and
00006  * enabling some additional data reports.
00007  *
00008  * This driver uses no dynamic allocation, but does allocate a couple hundred bytes of class variables as buffers.
00009  * This should allow you to monitor its memory usage using MBed's size printout.
00010  *
00011  * The BNO080 is a very complex chip; it's capable of monitoring and controlling other sensors and making
00012  * intelligent decisions and calculations using its data.  Accordingly, the protocol for communicating with it
00013  * is quite complex, and it took me quite a while to wrap my head around it.  If you need to modify or debug
00014  * this driver, look at the CPP file for an overview of the chip's communication protocol.
00015  *
00016  * Note: this driver only supports I2C.  I attempted to create an SPI version, but as far as I can tell,
00017  * the BNO's SPI interface has a bug that causes you to be unable to wake the chip from sleep in some conditions.
00018  * Until this is fixed, SPI on it is virtually unusable.
00019  */
00020 
00021 #ifndef HAMSTER_BNO080_H
00022 #define HAMSTER_BNO080_H
00023 
00024 #include <mbed.h>
00025 #include <quaternion.h>
00026 
00027 
00028 #include "BNO080Constants.h"
00029 
00030 // useful define when working with orientation quaternions
00031 #define SQRT_2 1.414213562f
00032 
00033 /**
00034   Class to drive the BNO080 9-axis IMU.
00035   
00036   There should be one instance of this class per IMU chip. I2C address and pin assignments are passed in the constructor.
00037 */
00038 class BNO080
00039 {
00040     /**
00041      * Serial stream to print debug info to.  Used for errors, and debugging output if debugging is enabled.
00042      */
00043     Serial * _debugPort;
00044 
00045     /**
00046      * I2C port object.  Provides physical layer communications with the chip.
00047      */
00048      
00049     I2C _i2cPort;
00050     //SoftI2C _i2cPort;
00051     
00052     /// user defined port speed
00053     int  _i2cPortSpeed;
00054 
00055     /// i2c address of IMU (7 bits)
00056     uint8_t _i2cAddress;
00057 
00058     /// Interrupt pin -- signals to the host that the IMU has data to send
00059     DigitalIn _int;
00060     
00061     // Reset pin -- resets IMU when held low.
00062     DigitalOut _rst;
00063 
00064     // packet storage
00065     //-----------------------------------------------------------------------------------------------------------------
00066 
00067 #define SHTP_HEADER_SIZE 4
00068 
00069     // Arbitrarily chosen, but should hopefully be large enough for all packets we need.
00070     // If you enable lots of sensor reports and get an error, you might need to increase this.
00071 #define STORED_PACKET_SIZE 128 
00072 
00073     /// Each SHTP packet has a header of 4 uint8_ts
00074     uint8_t shtpHeader[SHTP_HEADER_SIZE];
00075 
00076     /// Stores data contained in each packet.  Packets can contain an arbitrary amount of data, but 
00077     /// rarely get over a hundred bytes unless you have a million sensor reports enabled.
00078     /// The only long packets we actually care about are batched sensor data packets.
00079     uint8_t shtpData[STORED_PACKET_SIZE];
00080     
00081     #define READ_BUFFER_SIZE 512
00082     uint8_t readBuffer[READ_BUFFER_SIZE];
00083 
00084     /// Length of packet that was received into buffer.  Does NOT include header bytes.
00085     uint16_t packetLength;
00086 
00087     /// Current sequence number for each channel, incremented after transmission. 
00088     uint8_t sequenceNumber[6];
00089 
00090     /// Commands have a seqNum as well. These are inside command packet, the header uses its own seqNum per channel
00091     uint8_t commandSequenceNumber;
00092 
00093 
00094     // frs metadata
00095     //-----------------------------------------------------------------------------------------------------------------
00096 
00097     /// Record ID of the metadata record currently stored in the metadataRecord[] buffer.
00098     /// Used so that we can avoid requerying the FRS record if we need to make multiple metadata reads
00099     /// in succession.
00100     uint16_t bufferMetadataRecord;
00101 
00102     /// currently we only need the first 10 words of the metadata
00103 #define METADATA_BUFFER_LEN 10
00104 
00105     /// Buffer for current metadata record.
00106     uint32_t metadataRecord[METADATA_BUFFER_LEN];
00107 
00108     // data storage
00109     //-----------------------------------------------------------------------------------------------------------------
00110 
00111     // 1 larger than the largest sensor report ID
00112 #define STATUS_ARRAY_LEN MAX_SENSOR_REPORTID + 1
00113 
00114     /// stores status of each sensor, indexed by report ID
00115     uint8_t reportStatus[STATUS_ARRAY_LEN];
00116 
00117     /// stores whether a sensor has been updated since the last call to hasNewData()
00118     bool reportHasBeenUpdated[STATUS_ARRAY_LEN];
00119 
00120 public:
00121 
00122     // list of reports
00123     //-----------------------------------------------------------------------------------------------------------------
00124 
00125     /// List of all sensor reports that the IMU supports.
00126     enum Report
00127     {
00128         /**
00129          * Total acceleration of the IMU in world space.
00130          * See BNO datasheet section 2.1.1
00131          */
00132         TOTAL_ACCELERATION = SENSOR_REPORTID_ACCELEROMETER,
00133 
00134         /**
00135          * Acceleration of the IMU not including the acceleration of gravity.
00136          * See BNO datasheet section 2.1.1
00137          */
00138         LINEAR_ACCELERATION = SENSOR_REPORTID_LINEAR_ACCELERATION,
00139 
00140         /**
00141          * Acceleration of gravity felt by the IMU.
00142          * See BNO datasheet section 2.1.1
00143          */
00144         GRAVITY_ACCELERATION = SENSOR_REPORTID_GRAVITY,
00145 
00146         /**
00147          * (calibrated) gyroscope reading of the rotational speed of the IMU.
00148          * See BNO datasheet section 2.1.2
00149          */
00150         GYROSCOPE = SENSOR_REPORTID_GYROSCOPE_CALIBRATED,
00151 
00152         /**
00153          * (calibrated) reading of Earth's magnetic field levels.
00154          * See BNO datasheet section 2.1.3
00155          */
00156         MAG_FIELD = SENSOR_REPORTID_MAGNETIC_FIELD_CALIBRATED,
00157 
00158         /**
00159         * Uncalibrated reading of magnetic field levels, without any hard iron offsets applied
00160         * See BNO datasheet section 2.1.3
00161         */
00162         MAG_FIELD_UNCALIBRATED = SENSOR_REPORTID_MAGNETIC_FIELD_UNCALIBRATED,
00163 
00164         /**
00165          * Fused reading of the IMU's rotation in space using all three sensors.  This is the most accurate reading
00166          * of absolute orientation that the IMU can provide.
00167          * See BNO datasheet section 2.2.4
00168          */
00169         ROTATION = SENSOR_REPORTID_ROTATION_VECTOR,
00170 
00171         /**
00172          * Fused reading of rotation from accelerometer and magnetometer readings.  This report is designed to decrease
00173          * power consumption (by turning off the gyroscope) in exchange for reduced responsiveness.
00174          */
00175         GEOMAGNETIC_ROTATION = SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR,
00176 
00177         /**
00178          * Fused reading of the IMU's rotation in space.  Unlike the regular rotation vector, the Game Rotation Vector
00179          * is not referenced against the magnetic field and the "zero yaw" point is arbitrary.
00180          * See BNO datasheet section 2.2.2
00181          */
00182         GAME_ROTATION = SENSOR_REPORTID_GAME_ROTATION_VECTOR,
00183 
00184         /**
00185          * Detects a user tapping on the device containing the IMU.
00186          * See BNO datasheet section 2.4.2
00187          */
00188         TAP_DETECTOR = SENSOR_REPORTID_TAP_DETECTOR,
00189 
00190         /**
00191          * Detects whether the device is on a table, being held stably, or being moved.
00192          * See BNO datasheet section 2.4.1
00193          */
00194         STABILITY_CLASSIFIER = SENSOR_REPORTID_STABILITY_CLASSIFIER,
00195 
00196         /**
00197          * Detects a user taking a step with the IMU worn on their person.
00198          * See BNO datasheet section 2.4.3
00199          */
00200         STEP_DETECTOR = SENSOR_REPORTID_STEP_DETECTOR,
00201 
00202         /**
00203          * Detects how many steps a user has taken.
00204          * See BNO datasheet section 2.4.4
00205          */
00206         STEP_COUNTER = SENSOR_REPORTID_STEP_COUNTER,
00207 
00208         /**
00209          * Detects when the IMU has made a "significant" motion, defined as moving a few steps and/or accelerating significantly.
00210          *
00211          * NOTE: this report automatically disables itself after sending a report, so you'll have to reenable it each time a motion i s detected.
00212          * See BNO datasheet section 2.4.6
00213          */
00214         SIGNIFICANT_MOTION = SENSOR_REPORTID_SIGNIFICANT_MOTION,
00215 
00216         /**
00217          * Detects when the IMU is being shaken.
00218          * See BNO datasheet section 2.4.7
00219          */
00220         SHAKE_DETECTOR = SENSOR_REPORTID_SHAKE_DETECTOR
00221     };
00222 
00223     // data variables to read reports from
00224     //-----------------------------------------------------------------------------------------------------------------
00225 
00226     // @{
00227     /// Version info read from the IMU when it starts up
00228     uint8_t majorSoftwareVersion;
00229     uint8_t minorSoftwareVersion;
00230     uint16_t patchSoftwareVersion;
00231     uint32_t partNumber;
00232     uint32_t buildNumber;
00233     // @}
00234 
00235 
00236     /**
00237      * Readout from Accleration report.
00238      * Represents total acceleration in m/s^2 felt by the BNO's accelerometer.
00239      */
00240     TVector3  totalAcceleration;
00241 
00242     /**
00243      * Readout from Linear Acceleration report.
00244      * Represents acceleration felt in m/s^2 by the BNO's accelerometer not including the force of gravity.
00245      */
00246     TVector3  linearAcceleration;
00247 
00248     /**
00249      * Readout from Gravity report.
00250      * Represents the force of gravity in m/s^2 felt by the BNO's accelerometer.
00251      */
00252     TVector3  gravityAcceleration;
00253 
00254     /**
00255      * Readout from Calibrated Gyroscope report
00256      * Represents the angular velocities of the chip in rad/s in the X, Y, and Z axes
00257      */
00258     TVector3  gyroRotation;
00259 
00260     /**
00261      * Readout from the Magnetic Field Calibrated report.
00262      * Represents the magnetic field read by the chip in uT in the X, Y, and Z axes
00263      */
00264     TVector3  magField;
00265 
00266     /**
00267      * Readout from the Magnetic Field Uncalibrated report.
00268      * Represents the magnetic field read by the chip in uT in the X, Y, and Z axes, without hard iron offsets applied
00269      */
00270     TVector3  magFieldUncalibrated;
00271 
00272     /**
00273      * Auxiliary readout from the Magnetic Field Uncalibrated report.
00274      * Represents the hard iron offsets that the chip is using in each axis in uT.
00275      */
00276     TVector3  hardIronOffset;
00277 
00278     /**
00279      * Readout from the Rotation Vector report.
00280      * Represents the rotation of the IMU (relative to magnetic north) in radians.
00281      */
00282     Quaternion rotationVector;
00283 
00284     /**
00285      * Auxiliary accuracy readout from the Rotation Vector report.
00286      * Represents the estimated accuracy of the rotation vector in radians.
00287      */
00288     float rotationAccuracy;
00289 
00290     /**
00291      * Readout from the Game Rotation Vector report.
00292      * Represents the rotation of the IMU in radians.  Unlike the regular rotation vector, the Game Rotation Vector
00293      * is not referenced against the magnetic field and the "zero yaw" point is arbitrary.
00294      */
00295     Quaternion gameRotationVector;
00296 
00297     /**
00298      * Readout from the Geomagnetic Rotation Vector report.
00299      * Represents the geomagnetic rotation of the IMU (relative to magnetic north) in radians.
00300      */
00301     Quaternion geomagneticRotationVector;
00302 
00303     /**
00304      * Auxiliary accuracy readout from the Geomagnetic Rotation Vector report.
00305      * Represents the estimated accuracy of the rotation vector in radians.
00306      */
00307     float geomagneticRotationAccuracy;
00308 
00309     /**
00310      * Tap readout from the Tap Detector report.  This flag is set to true whenever a tap is detected, and you should
00311      * manually clear it when you have processed the tap.
00312      */
00313     bool tapDetected;
00314 
00315     /**
00316      * Whether the last tap detected was a single or double tap.
00317      */
00318     bool doubleTap;
00319 
00320     /**
00321      * Enum to represent the different stability types.
00322      *
00323      * See BNO datasheet section 2.4.1 and SH-2 section 6.5.31.2 for details.
00324      */
00325     enum Stability
00326     {
00327         /// Unknown stability type.
00328         UNKNOWN = 0,
00329 
00330         /// At rest on a stable surface with very little motion
00331         ON_TABLE = 1,
00332 
00333         /// Motion is stable, but the duration requirement for stability has not been met.
00334         /// Can only occur during gyroscope calibration (why? beats me!)
00335         STATIONARY = 2,
00336 
00337         /// Stable (has been below the acceleration threshold for the required duration)
00338         STABLE = 3,
00339 
00340         /// IMU is moving.
00341         MOTION = 4
00342     };
00343 
00344     /**
00345      * Readout from the stability classifier.
00346      * Current stability status of the IMU.
00347      */
00348     Stability stability;
00349 
00350     /**
00351      * Readout from the Step Detector report.  This flag is set to true whenever a step is detected, and you should
00352      * manually clear it when you have processed the step.
00353      */
00354     bool stepDetected;
00355 
00356     /**
00357      * Readout from the Step Counter report.  This count increases as the user takes steps, but can also decrease
00358      * if the IMU decides that a motion was not a step.
00359      */
00360     uint16_t stepCount;
00361 
00362     /**
00363      * Readout from the Significant Motion Detector report.  This flag is set to true whenever significant motion is detected, and you should
00364      * manually clear it when you have processed the event.
00365      */
00366     bool significantMotionDetected;
00367 
00368     /**
00369      * Readout from the Shake Detector report.  This flag is set to true whenever shaking is detected, and you should
00370      * manually clear it when you have processed the event.
00371      */
00372     bool shakeDetected;
00373 
00374     // @{
00375     /// The axis/axes that shaking was detected in in the latest shaking report.
00376     bool xAxisShake;
00377     bool yAxisShake;
00378     bool zAxisShake;
00379     // @}
00380 
00381     // Management functions
00382     //-----------------------------------------------------------------------------------------------------------------
00383 
00384     /**
00385      * Construct a BNO080, providing pins and parameters.
00386      *
00387      * This doesn't actally initialize the chip, you will need to call begin() for that.
00388      *
00389      * NOTE: while some schematics tell you to connect the BOOTN pin to the processor, this driver does not use or require it.
00390      * Just tie it to VCC per the datasheet.
00391      *
00392      * @param debugPort Serial port to write output to.  Cannot be nullptr.
00393      * @param user_SDApin Hardware I2C SDA pin connected to the IMU
00394      * @param user_SCLpin Hardware I2C SCL pin connected to the IMU
00395      * @param user_INTPin Input pin connected to HINTN
00396      * @param user_RSTPin Output pin connected to NRST
00397      * @param i2cAddress I2C address.  The BNO defaults to 0x4a, but can also be set to 0x4b via a pin.
00398      * @param i2cPortSpeed I2C frequency.  The BNO's max is 400kHz.
00399      */
00400     BNO080(Serial *debugPort, 
00401            PinName user_SDApin, 
00402            PinName user_SCLpin, 
00403            PinName user_INTPin, 
00404            PinName user_RSTPin,
00405            uint8_t i2cAddress=0x4a, 
00406            int i2cPortSpeed=100000);
00407 
00408     /**
00409      * Resets and connects to the IMU.  Verifies that it's connected, and reads out its version
00410      * info into the class variables above.
00411      *
00412      * If this function is failing, it would be a good idea to turn on BNO_DEBUG in the cpp file to get detailed output.
00413      *
00414      * @return whether or not initialization was successful
00415      */
00416     bool begin();
00417 
00418     /**
00419      * Tells the IMU to use its current rotation vector as the "zero" rotation vector and to reorient
00420      * all outputs accordingly.
00421      *
00422      * @param zOnly If true, only the rotation about the Z axis (the heading) will be tared.
00423      */
00424     void tare(bool zOnly = false);
00425 
00426     /**
00427      * Tells the IMU to begin a dynamic sensor calibration.  To calibrate the IMU, call this function and move
00428      * the IMU according to the instructions in the "BNO080 Sensor Calibration Procedure" app note
00429      * (http://www.hillcrestlabs.com/download/59de9014566d0727bd002ae7).
00430      *
00431      * To tell when the calibration is complete, look at the status bits for Game Rotation Vector (for accel and gyro)
00432      * and Magnetic Field (for the magnetometer).
00433      *
00434      * The gyro and accelerometer should only need to be calibrated once, but the magnetometer will need to be recalibrated
00435      * every time the orientation of ferrous metals around the IMU changes (e.g. when it is put into a new enclosure).
00436      *
00437      * The new calibration will not be saved in flash until you call saveCalibration().
00438      *
00439      * NOTE: calling this with all false values will cancel any calibration in progress.  However, the calibration data being created will
00440      * remain in use until the next chip reset (I think!)
00441      *
00442      * @param calibrateAccel Whether to calibrate the accelerometer.
00443      * @param calibrateGyro Whether to calibrate the gyro.
00444      * @param calibrateMag Whether to calibrate the magnetometer.
00445      *
00446      * @return whether the operation succeeded
00447      */
00448     bool enableCalibration(bool calibrateAccel, bool calibrateGyro, bool calibrateMag);
00449 
00450     /**
00451      * Saves the calibration started with startCalibration() and ends the calibration.
00452      * You will want to call this once the status bits read as "accuracy high".
00453      *
00454      * WARNING: if you paid for a factory calibrated IMU, then this WILL OVERWRITE THE FACTORY CALIBRATION in whatever sensors
00455      * are being calibrated.  Use with caution!
00456      *
00457      * @return whether the operation succeeded
00458      */
00459     bool saveCalibration();
00460 
00461     /**
00462      * Sets the orientation quaternion, telling the sensor how it's mounted
00463      * in relation to world space.
00464      * See page 40 of the BNO080 datasheet.
00465      *
00466      * NOTE: this driver provides the macro SQRT_2 to help with entering values from that table.
00467      *
00468      * NOTE 2: this setting does not persist and will have to be re-applied every time the chip is reset.
00469      * Use setPermanentOrientation() for that.
00470      *
00471      * @param orientation quaternion mapping from IMU space to world space.
00472      */
00473     void setSensorOrientation(Quaternion orientation);
00474 
00475     /**
00476      * Sets the orientation quaternion, telling the sensor how it's mounted
00477      * in relation to world space. See page 40 of the BNO080 datasheet.
00478      *
00479      * Unlike setSensorOrientation(), this setting will persist across sensor restarts.
00480      * However, it will also take a few hundred milliseconds to write.
00481      *
00482      * @param orientation quaternion mapping from IMU space to world space.
00483      *
00484      * @return true if the operation succeeded, false if it failed.
00485     */
00486     bool setPermanentOrientation(Quaternion orientation);
00487     
00488     // Report functions
00489     //-----------------------------------------------------------------------------------------------------------------
00490 
00491     /**
00492      * Checks for new data packets queued on the IMU.
00493      * If there are packets queued, receives all of them and updates
00494      * the class variables with the results.
00495      *
00496      * @return True iff new data packets of any kind were received.  If you need more fine-grained data change reporting,
00497      * check out hasNewData().
00498      */
00499     bool updateData();
00500 
00501 
00502     /**
00503      * Gets the status of a report as a 2 bit number.
00504      * per SH-2 section 6.5.1, this is interpreted as: <br>
00505      * 0 - unreliable <br>
00506      * 1 - accuracy low <br>
00507      * 2 - accuracy medium <br>
00508      * 3 - accuracy high <br>
00509      * of course, these are only updated if a given report is enabled.
00510      * @param report
00511      * @return
00512      */
00513     uint8_t getReportStatus(Report report);
00514 
00515     /**
00516      * Get a string for printout describing the status of a sensor.
00517      * @return
00518      */
00519     const char* getReportStatusString(Report report);
00520 
00521     /**
00522      * Checks if a specific report has gotten new data since the last call to this function.
00523      * @param report The report to check.
00524      * @return Whether the report has received new data.
00525      */
00526     bool hasNewData(Report report);
00527 
00528     /**
00529      * Enable a data report from the IMU.  Look at the comments above to see what the reports do.
00530      * This function checks your polling period against the report's max speed in the IMU's metadata,
00531      * and reports an error if you're trying to poll too fast.
00532      *
00533      * @param timeBetweenReports time in milliseconds between data updates.
00534      */
00535     void enableReport(Report report, uint16_t timeBetweenReports);
00536 
00537     /**
00538      * Disable a data report from the IMU.
00539      *
00540      * @param report The report to disable.
00541      */
00542     void disableReport(Report report);
00543 
00544     /**
00545      * Gets the serial number (used to uniquely identify each individual device).
00546      *
00547      * NOTE: this function should work according to the datasheet, but the device I was testing with appears to have
00548      * an empty serial number record as shipped, and I could never get anything out of it. Your mileage may vary.
00549      *
00550      * @return The serial number, or 0 on error.
00551      */
00552     uint32_t getSerialNumber();
00553 
00554     // Metadata functions
00555     //-----------------------------------------------------------------------------------------------------------------
00556 
00557     /**
00558      * Gets the range of a report as reported by the IMU.   Units are the same as the report's output data.
00559      * @return
00560      */
00561     float getRange(Report report);
00562 
00563     /**
00564      * Gets the resolution of a report as reported by the IMU.  Units are the same as the report's output data.
00565      * @param report
00566      * @return
00567      */
00568     float getResolution(Report report);
00569 
00570     /**
00571      * Get the power used by a report when it's operating, according to the IMU.
00572      * @param report
00573      * @return Power used in mA.
00574      */
00575     float getPower(Report report);
00576 
00577     /**
00578      * Gets the smallest polling period that a report supports.
00579      * @return Period in seconds.
00580      */
00581     float getMinPeriod(Report report);
00582 
00583     /**
00584      * Gets the larges polling period that a report supports.
00585      * Some reports don't have a max period, in which case this function will return -1.0.
00586      *
00587      * @return Period in seconds, or -1.0 on error.
00588      */
00589     float getMaxPeriod(Report report);
00590 
00591     /**
00592      * Prints a summary of a report's metadata to the
00593      * debug stream.  Should be useful for debugging and setting up reports since lots of this data
00594      * isn't given in the datasheets.
00595      *
00596      * Note: to save string constant space, this function is only available when BNO_DEBUG is 1.
00597      */
00598     void printMetadataSummary(Report report);
00599 
00600 private:
00601 
00602     // Internal metadata functions
00603     //-----------------------------------------------------------------------------------------------------------------
00604 
00605     /**
00606      * Gets the version of the metadata stored in the buffer.
00607      * We might see version 3 and 4 records, and they have different layouts.
00608      * @return
00609      */
00610     uint16_t getMetaVersion() {return static_cast<uint16_t>(metadataRecord[3] >> 16);}
00611 
00612     // @{
00613     /**
00614      * Gets the Q point from a report's metadata, which essentially defines where the decimal point goes in the sensor's output.
00615      * The 1/2/3 Q values are used in different places in the metadata, see SH-2 section 5.1 for details.
00616      * @param report
00617      * @return
00618      */
00619     int16_t getQ1(Report report);
00620     int16_t getQ2(Report report);
00621     int16_t getQ3(Report report);
00622     // @}
00623 
00624     // internal utility functions
00625     //-----------------------------------------------------------------------------------------------------------------
00626 
00627     /**
00628      * Processes the packet currently stored in the buffer, and updates class variables to reflect the data it contains
00629      */
00630     void processPacket();
00631 
00632     /**
00633      * Processes the sensor data packet currently stored in the buffer.
00634      * Only called from processPacket()
00635      */
00636     void parseSensorDataPacket();
00637 
00638     /**
00639      * Call to wait for a packet with the given parameters to come in.
00640      *
00641      * @param channel Channel of the packet
00642      * @param reportID Report ID (first data byte) of the packet
00643      * @param timeout how long to wait for the packet
00644      * @return true if the packet has been received, false if it timed out
00645      */
00646     bool waitForPacket(int channel, uint8_t reportID, float timeout = .125f);
00647 
00648     /**
00649      * Given a Q value, converts fixed point floating to regular floating point number.
00650      * @param fixedPointValue
00651      * @param qPoint
00652      * @return
00653      */
00654     float qToFloat(int16_t fixedPointValue, uint8_t qPoint);
00655 
00656     /**
00657      * Given a Q value, converts fixed point floating to regular floating point number.
00658      * This version is used for the unsigned 32-bit values in metadata records.
00659      * @param fixedPointValue
00660      * @param qPoint
00661      * @return
00662      */
00663     float qToFloat_dword(uint32_t fixedPointValue, int16_t qPoint);
00664 
00665     /**
00666      * Given a floating point value and a Q point, convert to Q
00667      * See https://en.wikipedia.org/wiki/Q_(number_format)
00668      * @param qFloat
00669      * @param qPoint
00670      * @return
00671      */
00672     int16_t floatToQ(float qFloat, uint8_t qPoint);
00673 
00674     /**
00675      * Given a floating point value and a Q point, convert to Q
00676      * See https://en.wikipedia.org/wiki/Q_(number_format)
00677      *
00678      * This version is used for the signed 32-bit values in metadata records.
00679      *
00680      * @param qFloat
00681      * @param qPoint
00682      * @return
00683      */
00684     int32_t floatToQ_dword(float qFloat, uint16_t qPoint);
00685 
00686     /**
00687      *  Tell the sensor to do a command.
00688      *  See SH-2 Reference Manual section 6.3.8 page 42, Command request
00689      *  The caller is expected to set shtpData 3 though 11 prior to calling
00690      */
00691     void sendCommand(uint8_t command);
00692 
00693     /**
00694      * Given a sensor's report ID, this tells the BNO080 to begin reporting the values.
00695      *
00696      * @param reportID
00697      * @param timeBetweenReports
00698      * @param specificConfig the specific config word. Useful for personal activity classifier.
00699      */
00700     void setFeatureCommand(uint8_t reportID, uint16_t timeBetweenReports, uint32_t specificConfig = 0);
00701 
00702     /**
00703      * Read a record from the FRS (Flash Record System) on the IMU.  FRS records are composed of 32-bit words,
00704      * with the size of each record determined by the record type.
00705      *
00706      * Will block until the entire record has been read.
00707      * @param recordID Record ID to read.  See SH-2 figures 28 and 29 for a list of these.  Sometimes also called
00708      * the "FRS Type" by the datasheet (???).
00709      * @param readBuffer Buffer to read data into.
00710      * @param readLength Amount of words to read from the record.  Must be <= the length of the record.
00711      *
00712      * @return whether the request succeeded
00713      */
00714     bool readFRSRecord(uint16_t recordID, uint32_t* readBuffer, uint16_t readLength);
00715 
00716     /**
00717      * Write a record to the FRS (Flash Record System) on the IMU.  FRS records are composed of 32-bit words,
00718      * with the size of each record determined by the record type.
00719      *
00720      * Will block until the entire record has been written.
00721      * @param recordID Record ID to write.  See SH-2 figures 28 and 29 for a list of these.  Sometimes also called
00722      * the "FRS Type" by the datasheet (???).
00723      * @param buffer Buffer to write data into.
00724      * @param length Amount of words to write to the record.  Must be <= the length of the record.
00725      *
00726      * @return whether the request succeeded
00727      */
00728     bool writeFRSRecord(uint16_t recordID, uint32_t* buffer, uint16_t length);
00729 
00730     /**
00731      * Reads a packet from the IMU and stores it in the class variables.
00732      *
00733      * @param timeout how long to wait for there to be a packet
00734      *
00735      * @return whether a packet was recieved.
00736      */
00737     bool receivePacket(float timeout=.2f);
00738 
00739     /**
00740      * Sends the current shtpData contents to the BNO.  It's a good idea to disable interrupts before you call this.
00741      *
00742      * @param channelNumber the channel to send on
00743      * @param dataLength How many bits of shtpData to send
00744      * @return
00745      */
00746     bool sendPacket(uint8_t channelNumber, uint8_t dataLength);
00747 
00748     /**
00749      * Prints the current shtp packet stored in the buffer.
00750      * @param length
00751      */
00752     void printPacket();
00753 
00754     /**
00755      * Erases the current SHTP packet buffer so new data can be written
00756      */
00757      void zeroBuffer();
00758 
00759      /**
00760       * Loads the metadata for this report into the metadata buffer.
00761       * @param report
00762       * @return Whether the operation succeeded.
00763       */
00764      bool loadReportMetadata(Report report);
00765 
00766 };
00767 
00768 
00769 #endif //HAMSTER_BNO080_H