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/hand/CAN_compatibility_arm.hpp"
00038
00039 using namespace std;
00040 using namespace ros;
00041 using namespace shadowrobot;
00042
00044
00046
00047 void run_publisher(boost::shared_ptr<SRPublisher> shadowarm_pub)
00048 {
00049 while( ok() )
00050 {
00051 shadowarm_pub->publish();
00052 }
00053 }
00054
00055
00067 int main(int argc, char** argv)
00068 {
00069 ros::init(argc, argv, "shadowarm");
00070 NodeHandle n;
00071
00072 boost::shared_ptr<CANCompatibilityArm> can_sa(new CANCompatibilityArm());
00073 boost::shared_ptr<SRSubscriber> shadowarm_subscriber(new SRSubscriber(can_sa));
00074
00075 boost::shared_ptr<SRPublisher> shadowarm_pub( new SRPublisher(can_sa));
00076
00077 boost::thread thrd2( boost::bind( &run_publisher, shadowarm_pub ));
00078 thrd2.join();
00079
00080 return 0;
00081 }