Go to the documentation of this file.00001 
00030 #include <ros/ros.h>
00031 
00032 #include <boost/thread.hpp>
00033 #include <boost/smart_ptr.hpp>
00034 
00035 #include "sr_hand/sr_subscriber.h"
00036 #include "sr_hand/sr_publisher.h"
00037 #include "sr_hand/sr_diagnosticer.h"
00038 
00039 #include "sr_hand/hand/real_arm.h"
00040 
00041 using namespace std;
00042 using namespace ros;
00043 using namespace shadowrobot;
00044 
00045 
00047 
00049 
00050 void run_diagnotics(boost::shared_ptr<SRDiagnosticer> shadowhand_diag)
00051 {
00052   while( ok() )
00053     shadowhand_diag->publish();
00054 }
00055 
00056 void run_publisher(boost::shared_ptr<SRPublisher> shadowhand_pub)
00057 {
00058   while( ok() )
00059     shadowhand_pub->publish();
00060 }
00061 
00062 
00073 int main(int argc, char** argv)
00074 {
00075   ros::init(argc, argv, "shadowarm");
00076   NodeHandle n;
00077 
00078   boost::shared_ptr<RealArm> real_arm( new RealArm() );
00079   boost::shared_ptr<SRSubscriber> shadowhand_subscriber(new SRSubscriber(real_arm));
00080 
00081   boost::shared_ptr<SRPublisher> shadowhand_pub( new SRPublisher(real_arm));
00082   boost::shared_ptr<SRDiagnosticer> shadowhand_diag( new SRDiagnosticer(real_arm, sr_arm_hardware));
00083 
00084   boost::thread thrd1( boost::bind( &run_diagnotics, shadowhand_diag ));
00085   boost::thread thrd2( boost::bind( &run_publisher, shadowhand_pub ));
00086   thrd1.join();
00087   thrd2.join();
00088 
00089   return 0;
00090 }