virtual_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"
39 
40 
41 using ros::NodeHandle;
42 using ros::ok;
48 
50 // MAIN //
52 
54 {
55  while (ok())
56  {
57  shadowhand_diag->publish();
58  }
59 }
60 
62 {
63  while (ok())
64  {
65  shadowhand_pub->publish();
66  }
67 }
68 
69 
80 int main(int argc, char **argv)
81 {
82  ros::init(argc, argv, "shadowarm");
83  NodeHandle n;
84 
86  boost::shared_ptr<SRSubscriber> shadowhand_subscriber(new SRSubscriber(virt_arm));
87 
88  boost::shared_ptr<SRPublisher> shadowhand_pub(new SRPublisher(virt_arm));
90 
91  boost::thread thrd1(boost::bind(&run_diagnotics, shadowhand_diag));
92  boost::thread thrd2(boost::bind(&run_publisher, shadowhand_pub));
93  thrd1.join();
94  thrd2.join();
95 
96  return 0;
97 }
void run_diagnotics(boost::shared_ptr< SRDiagnosticer > shadowhand_diag)
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)
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 virtual arm can be used as a simulator. It modelizes the Shadow Robot muscle arm.
int main(int argc, char **argv)
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