00001 #include "ati_force_sensor_driver_node.h" 00002 00003 AtiForceSensorDriverNode::AtiForceSensorDriverNode(ros::NodeHandle &nh) : 00004 iri_base_driver::IriBaseNodeDriver<AtiForceSensorDriver>(nh) 00005 { 00006 //init class attributes if necessary 00007 //this->loop_rate_ = 2;//in [Hz] 00008 00009 // [init publishers] 00010 this->netft_data_publisher_ = this->public_node_handle_.advertise<geometry_msgs::WrenchStamped>("netft_data", 100); 00011 00012 // [init subscribers] 00013 00014 // [init services] 00015 00016 // [init clients] 00017 00018 // [init action servers] 00019 00020 // [init action clients] 00021 00022 event_server_ = CEventServer::instance(); 00023 events_.push_back(driver_.getNewSampleEventId()); 00024 } 00025 00026 void AtiForceSensorDriverNode::mainNodeThread(void) 00027 { 00028 //lock access to driver if necessary 00029 00030 00031 // [fill msg Header if necessary] 00032 //<publisher_name>.header.stamp = ros::Time::now(); 00033 //<publisher_name>.header.frame_id = "<publisher_topic_name>"; 00034 00035 // [fill msg structures] 00036 //this->WrenchStamped_msg_.data = my_var; 00037 00038 // [fill srv structure and make request to the server] 00039 00040 // [fill action structure and make request to the action server] 00041 00042 // [publish messages] 00043 int event_id = event_server_->wait_first(events_); 00044 switch(event_id) 00045 { 00046 //New Sample Event 00047 case 0: 00048 ROS_DEBUG("New Sample Scan!"); 00049 this->driver_.lock(); 00050 WrenchStamped_msg_ = driver_.getData(); 00051 this->driver_.unlock(); 00052 00053 this->netft_data_publisher_.publish(this->WrenchStamped_msg_); 00054 break; 00055 default: 00056 ROS_ERROR("ATI event not handled!"); 00057 } 00058 //unlock access to driver if previously blocked 00059 } 00060 00061 /* [subscriber callbacks] */ 00062 00063 /* [service callbacks] */ 00064 00065 /* [action callbacks] */ 00066 00067 /* [action requests] */ 00068 00069 void AtiForceSensorDriverNode::postNodeOpenHook(void) 00070 { 00071 } 00072 00073 void AtiForceSensorDriverNode::addNodeDiagnostics(void) 00074 { 00075 } 00076 00077 void AtiForceSensorDriverNode::addNodeOpenedTests(void) 00078 { 00079 } 00080 00081 void AtiForceSensorDriverNode::addNodeStoppedTests(void) 00082 { 00083 } 00084 00085 void AtiForceSensorDriverNode::addNodeRunningTests(void) 00086 { 00087 } 00088 00089 void AtiForceSensorDriverNode::reconfigureNodeHook(int level) 00090 { 00091 } 00092 00093 AtiForceSensorDriverNode::~AtiForceSensorDriverNode(void) 00094 { 00095 // [free dynamic memory] 00096 } 00097 00098 /* main function */ 00099 int main(int argc,char *argv[]) 00100 { 00101 return driver_base::main<AtiForceSensorDriverNode>(argc, argv, "ati_force_sensor_driver_node"); 00102 }