00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #include <iostream>
00025
00026 #include "ros/ros.h"
00027 #include "geometry_msgs/Pose.h"
00028 #include "geometry_msgs/PoseStamped.h"
00029 #include <p2os_driver/MotorState.h>
00030 #include "tf/transform_datatypes.h"
00031 #include <p2os_driver/p2os.h>
00032
00033 int main( int argc, char** argv )
00034 {
00035 ros::init(argc,argv, "p2os");
00036 ros::NodeHandle n;
00037
00038 P2OSNode *p = new P2OSNode(n);
00039
00040 if( p->Setup() != 0 )
00041 {
00042 ROS_ERROR( "p2os setup failed..." );
00043 return -1;
00044 }
00045
00046 p->ResetRawPositions();
00047
00048 ros::Time lastTime;
00049
00050 while( ros::ok() )
00051 {
00052 p->check_and_set_vel();
00053 p->check_and_set_motor_state();
00054 p->check_and_set_gripper_state();
00055
00056 if( p->get_pulse() > 0 )
00057 {
00058 ros::Time currentTime = ros::Time::now();
00059 ros::Duration pulseInterval = currentTime - lastTime;
00060 if( pulseInterval.toSec() > p->get_pulse() )
00061 {
00062 ROS_DEBUG ("sending pulse" );
00063 p->SendPulse();
00064 lastTime = currentTime;
00065 }
00066 }
00067
00068
00069
00070
00071
00072
00073 p->SendReceive(NULL,true);
00074 p->updateDiagnostics();
00075 ros::spinOnce();
00076 }
00077
00078 if( p->Shutdown() != 0 )
00079 {
00080 ROS_WARN( "p2os shutdown failed... your robot might be heading for the wall?" );
00081 }
00082
00083 ROS_INFO( "Quitting... " );
00084 return 0;
00085
00086 }