bmc050_node.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 // ROS headers
00040 #include <ros/ros.h>
00041 #include <ros/time.h>
00042 
00043 #include <bmc050.hpp>
00044 #include <sub20_interface.hpp> 
00045 
00046 // ROS message
00047 #include <bmc050_driver/bmc050_measurement.h>
00048 
00049 int main( int argc, char **argv )
00050 {
00051   
00052   //ROS initialization and publisher/subscriber setup
00053   ros::init( argc, argv, "bmc050_node" );
00054   ros::NodeHandle nh;
00055 
00056   std::string hw_id;
00057   int number_of_bmc050_sensors;
00058   int publish_rate_Hz;
00059 
00060   // Get parameters from .launch file or parameter server, or take defaults
00061   nh.param<int>( "/bmc050_node/number_of_bmc050_sensors", number_of_bmc050_sensors, 1 );
00062   nh.param<int>( "/bmc050_node/publish_rate_Hz", publish_rate_Hz, 50 );
00063   nh.param<std::string>( "/bmc050_node/hardware_id", hw_id, "0208" );
00064 
00065   Sub20Interface sub20( hw_id );
00066   std::vector<BMC050*> BMC050_Chain;
00067   
00068   // Intantiate the array of BMC050s
00069   for( int i = 0; i < number_of_bmc050_sensors; i++ )
00070   {
00071     // instantiate a sensor and pass in a pointer to it's hw interface:
00072     BMC050* eCompass = new BMC050( &sub20 ); 
00073   
00074     eCompass->setProtocol( SPI ); 
00075     eCompass->setFrequency( 125000 );
00076     eCompass->setCompassPin( i*2 ); // SS0 on the sub20
00077     eCompass->setAccelPin( i*2 + 1 ); // SS1 on the sub20
00078     // NOTE: in SPI mode, the BMC050 pins PS1 and PS2 connected to GND.
00079 
00080     // tweak accelerometer settings:
00081     //eCompass->setAccelRange( BMC050Parameters::RANGE_4 ); // adjusts for the sensitivity AND changes the range in the initialization process.
00082     //eCompass->setAccelBandwidth( BMC050Parameters::BW_63HZ );
00083     //eCompass->setFilter( true ); // get filtered data upon initializing
00084     // tweak compass settings:
00085     //eCompass->setCompassRate( BMC050Parameters::ODR_30HZ );
00086     //eCompass->setNumRepetitionsXY( 31 );
00087     //eCompass->setNumRepetitionsZ( 31 );
00088 
00089     // Initialize that BMC050_Chain member:
00090     if( eCompass->initialize() == false )
00091     {
00092       ROS_ERROR( "BMC050 device: %d initialization failed.", i );
00093       return 1;
00094     }
00095     //eCompass->simpleCalibrationAccel();
00096 
00097     // push the bosch_imu instance onto the stack:
00098     BMC050_Chain.push_back( eCompass );
00099   }
00100   
00101   // instantiate a message:
00102   bmc050_driver::bmc050_measurement msg;
00103   ros::Publisher bmc050_pub = nh.advertise<bmc050_driver::bmc050_measurement>("BMC050_data", 20 );
00104 
00105   //set loop rate for measurement polling
00106   ros::Rate loop_rate_Hz( publish_rate_Hz );
00107     
00108   // Run sensor node:
00109   while( nh.ok() )
00110   {
00111     // remove old data on all vectors, so data doesn't accumulate:
00112     msg.AccelerationX.clear();
00113     msg.AccelerationY.clear();
00114     msg.AccelerationZ.clear();
00115     msg.Temperature.clear();
00116     msg.MagneticFieldIntensityX.clear();
00117     msg.MagneticFieldIntensityY.clear();
00118     msg.MagneticFieldIntensityZ.clear();
00119     msg.HallResistance.clear();
00120   
00121     for( int i = 0; i < number_of_bmc050_sensors; i++ )
00122     { 
00123       // take measurement
00124       if( BMC050_Chain[i]->takeMeasurement() == false )
00125       {
00126         ROS_ERROR( "BMC050 device %d failed. Node failed.", i );
00127         return 1;
00128       }
00129 
00130       msg.AccelerationX.push_back( BMC050_Chain[i]->AccelX_ );
00131       msg.AccelerationY.push_back( BMC050_Chain[i]->AccelY_ );
00132       msg.AccelerationZ.push_back( BMC050_Chain[i]->AccelZ_ );
00133       msg.Temperature.push_back( BMC050_Chain[i]->Temperature_ );
00134       msg.MagneticFieldIntensityX.push_back( BMC050_Chain[i]->CompassX_ );
00135       msg.MagneticFieldIntensityY.push_back( BMC050_Chain[i]->CompassY_ );
00136       msg.MagneticFieldIntensityZ.push_back( BMC050_Chain[i]->CompassZ_ );
00137       msg.HallResistance.push_back( BMC050_Chain[i]->RHall_ );
00138     }
00139     msg.header.stamp = ros::Time::now();
00140 
00141     bmc050_pub.publish( msg ); 
00142 
00143     ros::spinOnce();
00144     loop_rate_Hz.sleep();
00145   }
00146 
00147   ROS_WARN( "Closing BMC050 driver." );
00148   return 0;
00149 }


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