real_arm_node.cpp
Go to the documentation of this file.
1 
30 #include <ros/ros.h>
31 
32 #include <boost/thread/thread.hpp>
33 #include <boost/smart_ptr.hpp>
34 
35 #include "sr_hand/sr_subscriber.h"
36 #include "sr_hand/sr_publisher.h"
38 #include "sr_hand/hand/real_arm.h"
39 
40 using ros::NodeHandle;
41 using ros::ok;
47 
49 // MAIN //
51 
53 {
54  while (ok())
55  {
56  shadowhand_diag->publish();
57  }
58 }
59 
61 {
62  while (ok())
63  {
64  shadowhand_pub->publish();
65  }
66 }
67 
68 
79 int main(int argc, char **argv)
80 {
81  ros::init(argc, argv, "shadowarm");
82  NodeHandle n;
83 
84  boost::shared_ptr <RealArm> real_arm(new RealArm());
85  boost::shared_ptr <SRSubscriber> shadowhand_subscriber(new SRSubscriber(real_arm));
86 
87  boost::shared_ptr <SRPublisher> shadowhand_pub(new SRPublisher(real_arm));
89 
90  boost::thread
91  thrd1(boost::bind(&run_diagnotics, shadowhand_diag));
92  boost::thread
93  thrd2(boost::bind(&run_publisher, shadowhand_pub));
94  thrd1.join();
95  thrd2.join();
96 
97  return 0;
98 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void run_publisher(boost::shared_ptr< SRPublisher > shadowhand_pub)
int main(int argc, char **argv)
The Diagnosticer is a ROS publisher which publishes diagnostic data regarding the Dextrous Hand or th...
This class reads and publishes data concerning the shadowhand / shadowarm. To publish those data...
ROSCPP_DECL bool ok()
The real arm is a ROS interface to Shadow Robot muscle arm.
void run_diagnotics(boost::shared_ptr< SRDiagnosticer > shadowhand_diag)
This ROS subscriber is used to issue commands to the hand / arm, from sending a set of targets...


sr_hand
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:53