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 <bmc050.hpp> 00043 #include <arduino_interface.hpp> 00044 00045 using namespace bosch_drivers_common; 00046 00047 int main( int argc, char** argv ) 00048 { 00049 // Create an Arduino Bosch Hardware interface 00050 ArduinoInterface Arduino( "/dev/ttyACM1" ); 00051 00052 // Instantiate a sensor, and pass pointers to it's hardware interface and its parameters: 00053 BMC050 DualSensor( &Arduino ); 00054 00055 DualSensor.setProtocol( I2C ); 00056 DualSensor.setFrequency( 400000 ); 00057 00058 // the hardware configuration determines the compass and accelerometer i2c addresses: 00059 DualSensor.setCSB2( 0 ); 00060 DualSensor.setSDO( 0 ); 00061 00062 // tweak accelerometer settings: 00063 DualSensor.setAccelRange( BMC050Parameters::RANGE_8 ); // adjusts for the sensitivity AND changes the range in the initialization process. 00064 DualSensor.setAccelBandwidth( BMC050Parameters::BW_63HZ ); 00065 DualSensor.setFilter( true ); // get filtered data upon initializing 00066 DualSensor.setCompassRate( BMC050Parameters::ODR_25HZ ); 00067 00068 // Initialize the Driver (and hardware) with sensor-specific parameters: 00069 bool init_success = DualSensor.initialize(); 00070 00071 if( init_success == false ) 00072 { 00073 ROS_ERROR("Sensor initialization failed."); 00074 return 1; 00075 } 00076 00077 bool run_continuous_ = true; 00078 00079 // Initialize time, since we're not actually creating a node: 00080 ros::Time::init(); 00081 ros::Rate wait_interval( 50 ); 00082 00083 double MagX, MagY, MagZ, AccX, AccY, AccZ, Temp; 00084 uint16_t RHall; 00085 00086 while( run_continuous_ ) 00087 { 00088 if( DualSensor.takeMeasurement() == false ) 00089 break; 00090 00091 MagX = DualSensor.CompassX_; 00092 MagY = DualSensor.CompassY_; 00093 MagZ = DualSensor.CompassZ_; 00094 Temp = DualSensor.Temperature_; 00095 AccX = DualSensor.AccelX_; 00096 AccY = DualSensor.AccelY_; 00097 AccZ = DualSensor.AccelZ_; 00098 RHall = DualSensor.RHall_; 00099 00100 //ROS_INFO("RHall: %d",RHall); 00101 ROS_INFO("CompassX: %f", MagX); 00102 ROS_INFO("CompassY: %f", MagY); 00103 ROS_INFO("CompassZ: %f", MagZ); 00104 //ROS_INFO("Accel_Temp: %f", Temp); 00105 ROS_INFO("AccelerometerX: %f", AccX); 00106 ROS_INFO("AccelerometerY: %f",AccY); 00107 ROS_INFO("AccelerometerZ: %f\r\n\r\n", AccZ); 00108 00109 wait_interval.sleep(); 00110 } 00111 ROS_ERROR("BMC050 node exiting."); 00112 00113 return 0; 00114 }