00001 00002 #include "FRIData.hh" 00003 #include <pthread.h> 00004 00005 #include <string> 00006 00007 #include <ros/ros.h> 00008 #include <diagnostic_updater/diagnostic_updater.h> 00009 #include <sensor_msgs/JointState.h> 00010 #include <kuka_fri/ImpedanceCommand.h> 00011 #include <soft_runstop/Handler.h> 00012 00013 class FRIThread; 00014 00015 class ROSComm { 00016 public: 00017 ROSComm(); 00018 ~ROSComm(); 00019 bool configure(FRIThread *fri); 00020 bool open(); 00021 void publishData(const RobotData &data, const RobotCommand &cmd); 00022 void publishStatus(const RobotStatus &status); 00023 bool runstop(); 00024 00025 // threading support 00026 void start(FRIThread *fri); 00027 void finish(); 00028 private: 00029 std::string side_; 00030 soft_runstop::Handler* soft_runstop_handler_; 00031 RobotStatus status_; 00032 void status_update(diagnostic_updater::DiagnosticStatusWrapper &s); 00033 void runstop_receiver(const std_msgs::BoolConstPtr &msg); 00034 void impedanceCommand(const kuka_fri::ImpedanceCommand::ConstPtr& msg); 00035 ros::NodeHandle *n_; 00036 ros::Publisher pub_; 00037 ros::Subscriber sub_; 00038 00039 diagnostic_updater::Updater *diagnostic_; 00040 sensor_msgs::JointState joint_state_; 00041 00042 // threading support 00043 FRIThread* fri_; 00044 double rate_; 00045 void* run(); 00046 static void* run_s(void *ptr) { return ((ROSComm *) ptr)->run(); } 00047 00048 pthread_t thread_; 00049 bool running_, exitRequested_; 00050 };