example_bma180_i2c_sub20.cpp
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 //\Author Joshua Vasquez and Philip Roan, Robert Bosch LLC
00038 
00039 #include <ros/ros.h>
00040 #include <ros/time.h>
00041 
00042 #include <bma180.hpp>
00043 #include <sub20_interface.hpp> 
00044 
00045 using namespace bosch_drivers_common;
00046 
00047 int main( int argc, char** argv )
00048 {
00049   // Create a Bosch Hardware interface
00050   Sub20Interface Sub20( "0208" );
00051 
00052   // Instantiate a sensor, and pass in the address of its hw interface:
00053   BMA180 AccelSensor( &Sub20 ); 
00054   AccelSensor.setProtocol( I2C ); // CSB connected to VDD
00055   AccelSensor.setFrequency( 400000 );
00056  
00057   AccelSensor.setSlaveAddressBit( 0 ); // SDO connected to VSS
00058  
00059   AccelSensor.setAccelRange( BMA180Parameters::RANGE_16 );
00060   AccelSensor.setBandwidth( BMA180Parameters::BW_150 );
00061   AccelSensor.setPreCalOffsets( true ); // enables precalibrated offsets. Disabled by default.
00062 
00063   // Initialize the Driver (and hardware) with sensor-specific parameters:
00064   if( AccelSensor.initialize() == false )
00065   {
00066     ROS_ERROR("Accel Sensor initialization failed.");
00067     return 1;
00068   }
00069 
00070   sleep( 3 ); // to read the register values.
00071 
00072   bool run_continuous_ = true;
00073 
00074   // Initialize ROS's time, since we're not actually creating a node:
00075   ros::Time::init();
00076   // create a loop rate:
00077   ros::Rate wait_interval( 20 ); 
00078    
00079   while( run_continuous_)
00080   {
00081     AccelSensor.takeMeasurement();
00082   
00083     ROS_INFO("Accel_X: %f", AccelSensor.AccelX_);
00084     ROS_INFO("Accel_Y: %f", AccelSensor.AccelY_);
00085     ROS_INFO("Accel_Z: %f", AccelSensor.AccelZ_);
00086     
00087     wait_interval.sleep();
00088     
00089     /*
00090      * NOTE: if you wish to change the accel_range dynamically (NOT RECOMMENDED ON DATASHEET),
00091      * you must do two function calls:
00092      * 1. AccelSensor.setAccelRange( newRange)
00093      * 2. AccelSensor.changeAccelRange()
00094      * so that both the class and the sensor interpret the data correctly.
00095      */
00096   }
00097  
00098   return 0;
00099 }


bosch_drivers_example_nodes
Author(s): Joshua Vasquez, Philip Roan. Maintained by Philip Roan
autogenerated on Sat Dec 28 2013 16:49:21