encoder_node.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 and Philip Roan, Robert Bosch LLC
00038 
00039 // ROS headers
00040 #include <ros/ros.h>
00041 
00042 #include <encoder_driver/encoder_driver.h>
00043 #include <arduino_interface.hpp> 
00044 
00045 int main( int argc, char **argv )
00046 {
00047   
00048   //ROS initialization and publisher/subscriber setup
00049   ros::init( argc, argv, "Encoder_Driver" );
00050   ros::NodeHandle nh("~");
00051 
00052   std::string hw_id;
00053   
00054   // Get parameters from .launch file or parameter server, or take defaults
00055   nh.param<std::string>( "hardware_id", hw_id, "/dev/ttyACM0" );
00056 
00057   ROS_INFO("Initializing Arduino");
00058   NewArduinoInterface Arduino( hw_id );
00059   Arduino.initialize();
00060 
00061   ROS_INFO("Creating fast Encoder");  
00062   // create new encoder driver using pins 3 and 4
00063   EncoderDriver* encoder_driver = new EncoderDriver( &Arduino , 4, 3 ); 
00064   encoder_driver->invertOutput();
00065   
00066   ROS_INFO("Initializing Encoder");
00067   if( encoder_driver->initialize() == false)
00068   {
00069     ROS_ERROR("Error initializing encoder driver");
00070     return -1;
00071   }
00072 
00073   ROS_INFO("Creating slow Encoder");  
00074   // create new encoder driver using pins 5 and 6
00075   EncoderDriver* encoder_driver2 = new EncoderDriver( &Arduino , 5, 6 ); 
00076 
00077   ROS_INFO("Initializing slow Encoder");
00078   if( encoder_driver2->initialize() == false)
00079   {
00080     ROS_ERROR("Error initializing encoder driver");
00081     return -1;
00082   }
00083         
00084   ros::Rate loop_rate_Hz(1);
00085 
00086   int64_t position, position2;
00087   ROS_INFO("Setting initial position");
00088   encoder_driver->setPosition(0);
00089   encoder_driver2->setPosition(0);
00090 
00091   ROS_INFO("Start reading current position every second...");
00092 
00093   while( nh.ok() )
00094   {
00095     position = encoder_driver->getPosition();
00096     
00097     position2 = encoder_driver2->getPosition();
00098 
00099     ROS_INFO("Position1: %li    Position2: %li", position, position2);
00100     
00101     ros::spinOnce();
00102     loop_rate_Hz.sleep();
00103   }
00104   
00105   ROS_WARN( "Closing encoder driver." );
00106   return 0;  
00107 }


bosch_drivers_basic_nodes
Author(s): Joshua Vasquez, Philip Roan. Maintained by Philip Roan
autogenerated on Mon Oct 6 2014 10:10:31