Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
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
00049 ros::init( argc, argv, "Encoder_Driver" );
00050 ros::NodeHandle nh("~");
00051
00052 std::string hw_id;
00053
00054
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
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
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 }