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 #include "sr_hand/hand/etherCAT_compatibility_hand.hpp"
00039
00040 using namespace std;
00041 using namespace ros;
00042 using namespace shadowrobot;
00043
00045
00047
00048 void run_diagnotics(boost::shared_ptr<SRDiagnosticer> shadowhand_diag)
00049 {
00050 while( ok() )
00051 {
00052 shadowhand_diag->publish();
00053 }
00054 }
00055
00056 void run_publisher(boost::shared_ptr<SRPublisher> shadowhand_pub)
00057 {
00058 while( ok() )
00059 {
00060 shadowhand_pub->publish();
00061 }
00062 }
00063
00064
00076 int main(int argc, char** argv)
00077 {
00078 ros::init(argc, argv, "shadowhand");
00079 NodeHandle n;
00080
00081 boost::shared_ptr<EtherCATCompatibilityHand> eth_sh(new EtherCATCompatibilityHand());
00082 boost::shared_ptr<SRSubscriber> shadowhand_subscriber(new SRSubscriber(eth_sh));
00083
00084
00085 boost::shared_ptr<SRPublisher> shadowhand_pub( new SRPublisher(eth_sh));
00086 boost::shared_ptr<SRDiagnosticer> shadowhand_diag( new SRDiagnosticer(eth_sh, sr_hand_hardware));
00087
00088 boost::thread thrd1( boost::bind( &run_diagnotics, shadowhand_diag ));
00089 boost::thread thrd2( boost::bind( &run_publisher, shadowhand_pub ));
00090 thrd1.join();
00091 thrd2.join();
00092
00093 return 0;
00094 }