32 #include <boost/thread/thread.hpp> 33 #include <boost/smart_ptr.hpp> 57 shadowhand_diag->publish();
65 shadowhand_pub->publish();
80 int main(
int argc,
char **argv)
91 boost::thread thrd1(boost::bind(&
run_diagnotics, shadowhand_diag));
92 boost::thread thrd2(boost::bind(&
run_publisher, shadowhand_pub));
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...
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...