encoder_driver.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2013, 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 Kai Franke, Robert Bosch LLC
00038 
00039 #include "encoder_driver/encoder_driver.h"
00040 
00041 EncoderDriver::EncoderDriver( bosch_hardware_interface* hw, uint8_t encoder1_pin, uint8_t encoder2_pin ): sensor_driver( hw )
00042 {
00043   // variable to automaticly define encoder object id starting with 0
00044   static uint8_t encoder_id = 0;
00045   
00046   _encoder1_pin = encoder1_pin;
00047   _encoder2_pin = encoder2_pin;
00048   _encoder_id = encoder_id;
00049   _last_position = 0;
00050   _overflow = 0;
00051   invert_ = 1;
00052   
00053   // Determine encoder ID 
00054   if (encoder_id < 16)
00055   {
00056     int frequency = 0; // does not apply for Encoder
00057     int flags[3] = { CREATE, _encoder1_pin, _encoder2_pin };  // indicates that we want to create the object on the hardware device
00058     flags[0] |= encoder_id << 4; // writes the object id to the upper 4 bits. encoder_id will tell the hardware device which object to create
00059     uint8_t reg = 0; // does not apply for Encoder
00060     uint8_t data[0]; // not needed for constructor
00061     uint8_t num_bytes = 0; // will not be read
00062     if( _encoder1_pin == _encoder2_pin )
00063     {
00064       ROS_ERROR("EncoderDriver::EncoderDriver(): Encoder pins must be different");
00065     }
00066     else
00067     {
00068       if( hardware_->write( getDeviceAddress(), ENCODER, frequency, flags, reg, data, num_bytes ) < 0 )
00069       {
00070         ROS_ERROR("EncoderDriver::~EncoderDriver(): could not create object on hardware device");
00071       }
00072     }
00073     ++encoder_id; // increase number ob created objects
00074   }
00075   else
00076   {
00077     ROS_ERROR("Maximum number of Encoder objects(16) exceeded, will not create any more");
00078   }
00079 }
00080 
00081 EncoderDriver::EncoderDriver( bosch_hardware_interface* hw, uint8_t encoder_id ): sensor_driver( hw )
00082 {
00083   // set encoder pins to same value to indicate that there was no object created on the serial device
00084   _encoder1_pin = _encoder2_pin = 255;
00085   // assign this instance to the desired instance on the serial device
00086   _encoder_id = encoder_id; 
00087   _last_position = 0;
00088   _overflow = 0;
00089   invert_ = 1;
00090   
00091   // Determine encoder ID 
00092   if (encoder_id >= 16)
00093   {
00094     ROS_ERROR("Select an encoder_id [0..15] which was already created on the serial device");
00095   }
00096 }
00097 
00098 // destroys the object created on the hardware device
00099 EncoderDriver::~EncoderDriver()
00100 {
00101   // check if instance on serial device needs to be destroyed
00102   if( _encoder1_pin != _encoder2_pin )  // indicates that object was created on serial device
00103   {
00104     int frequency = 0; // does not apply for Encoder
00105     int flags[1] = { DESTROY }; // indicates that we want to destroy the object on the hardware device
00106     flags[0] |= _encoder_id << 4; // writes the object id to the upper 4 bits. encoder_id will tell the hardware device which object to destroy
00107     uint8_t reg = 0; // does not apply for Encoder
00108     uint8_t data[0]; // not needed for destructor
00109     uint8_t num_bytes = 0; // will not be read
00110     
00111     if( hardware_->write( getDeviceAddress(), ENCODER, frequency, flags, reg, data, num_bytes ) < 0 )
00112     {
00113       ROS_ERROR("EncoderDriver::~EncoderDriver(): could not destroy object on hardware device");
00114     }
00115   }
00116 }
00117 
00118 uint8_t EncoderDriver::getDeviceAddress()
00119 {
00120   // the answer to all questions + 3
00121   return 45;
00122 }
00123 
00124 bool EncoderDriver::initialize()
00125 { 
00126   if( _encoder1_pin == _encoder2_pin )
00127   {
00128     ROS_WARN("EncoderDriver::initialize(): This encoder has already been initialized");
00129     return true;
00130   }
00131   
00132   // Initialize the hardware interface
00133   if( hardware_->initialize() == false )
00134   {
00135     ROS_ERROR("PwmDriver::initialize(): Could not initialize a hardware interface!");
00136     return false;
00137   }
00138   // reset encoder position to 0
00139   if(! EncoderDriver::setPosition(0) )
00140     return false;
00141   
00142   return true;
00143 }
00144 
00145 uint8_t EncoderDriver::getEncoderID( )
00146 {
00147   return _encoder_id;
00148 }
00149 
00150 int64_t EncoderDriver::getPosition()
00151 {
00152   int frequency = 0; // does not apply for Encoder
00153   int flags[1];
00154   flags[0] = _encoder_id << 4; // writes the object id to the upper 4 bits. encoder_id will tell the hardware device which encoder object to read from
00155   uint8_t reg = 0; // does not apply for Encoder
00156   uint8_t data[4]; // will store the data after successful read call
00157   uint8_t num_bytes = 4; // will not be read because it is always 4 bytes
00158   int32_t position; // return value
00159   
00160   if( hardware_->read( getDeviceAddress(), ENCODER, frequency, flags, reg, data, num_bytes ) < 0 )
00161   {
00162     ROS_ERROR("EncoderDriver::getPosition(): could not read input");
00163     return false;
00164   } 
00165   // convert read data to int32_t
00166   uint32_t temp[4];
00167   temp[0] = data[0];
00168   temp[1] = data[1];
00169   temp[2] = data[2];
00170   temp[3] = data[3];
00171   position  = temp[0] << 24;
00172   position |= temp[1] << 16;
00173   position |= temp[2] << 8;
00174   position |= temp[3] << 0;
00175   
00176   if( _last_position > (1 << 30) )  // was last position greater than one billion?
00177   {
00178     if( position < 0 ) // assume there was an overflow
00179     {
00180       ++_overflow;
00181     }
00182   }
00183   else if( _last_position < (-1) * (1 << 30) )  // was last position smaller than negative one billion?
00184   {
00185     if( position > 0 )  // assume there was an underflow
00186     {
00187       --_overflow;
00188     }
00189   }
00190   _last_position = position;
00191   
00192   return ((_overflow * 4294967296) + position) * invert_ ;
00193 }
00194 
00195 bool EncoderDriver::setPosition( int32_t position )
00196 {
00197   position *= invert_;  // invert if encoder values are inverted, too
00198   _overflow = 0;  // reset overflow
00199   int frequency = 0; // does not apply for Encoder
00200   int flags[3] = { SET_POSITION, _encoder1_pin, _encoder2_pin };
00201   flags[0] |= _encoder_id << 4; // writes the object id to the upper 4 bits. encoder_id will tell the hardware device which encoder object to write to
00202   uint8_t reg = 0; // does not apply for Encoder
00203   uint8_t data[4]; // will contain split up position
00204   uint8_t num_bytes = 4; // will not be read because it is always 4 bytes
00205   
00206   // split position into 4 bytes for transmission
00207   uint32_t temp;
00208   temp = ((position & 0xFF000000) >> 24);
00209   data[0] = (uint8_t)temp;
00210   temp = ((position & 0x00FF0000) >> 16);
00211   data[1] = (uint8_t)temp;
00212   temp = ((position & 0x0000FF00) >> 8);
00213   data[2] = (uint8_t)temp;
00214   temp = ((position & 0x000000FF) >> 0);
00215   data[3] = (uint8_t)temp;
00216   
00217   if( hardware_->write( getDeviceAddress(), ENCODER, frequency, flags, reg, data, num_bytes ) < 0 )
00218   {
00219     ROS_ERROR("EncoderDriver::setPosition(): could not write position");
00220     return false;
00221   } 
00222   return true;
00223 }
00224 
00225 void EncoderDriver::invertOutput( )
00226 {
00227   invert_ *= -1;
00228 }


encoder_driver
Author(s): Kai Franke
autogenerated on Sat Dec 28 2013 16:50:09