00001 #include "kinton_arm_node.h" 00002 00003 using namespace std; 00004 00005 KintonArmDriverNode::KintonArmDriverNode(ros::NodeHandle &nh) : 00006 iri_base_driver::IriBaseNodeDriver<KintonArmDriver>(nh) 00007 { 00008 //init class attributes if necessary 00009 //this->loop_rate_ = 2;//in [Hz] 00010 this->new_pos_.resize(5); 00011 this->new_pos_.reserve(5); 00012 this->new_pos_.clear(); 00013 this->new_pos_.push_back(90); 00014 this->new_pos_.push_back(160); 00015 this->new_pos_.push_back(180); 00016 this->new_pos_.push_back(20); 00017 this->new_pos_.push_back(90); 00018 00019 // [init publishers] 00020 this->arm_joint_feedback_publisher_ = this->public_node_handle_.advertise<sensor_msgs::JointState>("arm_joint_feedback", 10); 00021 00022 // [init subscribers] 00023 this->arm_joint_pos_subscriber_ = this->public_node_handle_.subscribe("arm_joint_pos", 10, &KintonArmDriverNode::arm_joint_pos_callback, this); 00024 00025 // [init services] 00026 00027 // [init clients] 00028 00029 // [init action servers] 00030 00031 // [init action clients] 00032 } 00033 00034 void KintonArmDriverNode::mainNodeThread(void) 00035 { 00036 //lock access to driver if necessary 00037 //this->driver_.lock(); 00038 00039 this->driver_.set_new_positions(this->new_pos_); 00040 00041 // [fill msg Header if necessary] 00042 this->JointState_msg_.header.stamp = ros::Time::now(); 00043 // [fill msg structures] 00044 // Without feedback, the Joint state message is the same 00045 00046 this->JointState_msg_.position.clear(); 00047 this->JointState_msg_.velocity.clear(); 00048 this->JointState_msg_.name.clear(); 00049 00050 this->JointState_msg_.name.push_back("joint1"); 00051 this->JointState_msg_.name.push_back("joint2"); 00052 this->JointState_msg_.name.push_back("joint3"); 00053 this->JointState_msg_.name.push_back("joint4"); 00054 this->JointState_msg_.name.push_back("joint5"); 00055 00056 for(size_t i=0;i<this->new_pos_.size();i++) 00057 { 00058 // convert from degrees to radians 00059 this->JointState_msg_.position.push_back(this->new_pos_[i]*3.14159/180.0); 00060 this->JointState_msg_.velocity.push_back(0.0); 00061 } 00062 00063 // [fill srv structure and make request to the server] 00064 00065 // [fill action structure and make request to the action server] 00066 00067 // [publish messages] 00068 this->arm_joint_feedback_publisher_.publish(this->JointState_msg_); 00069 00070 //unlock access to driver if previously blocked 00071 //this->driver_.unlock(); 00072 } 00073 00074 /* [subscriber callbacks] */ 00075 void KintonArmDriverNode::arm_joint_pos_callback(const sensor_msgs::JointState::ConstPtr& msg) 00076 { 00077 //ROS_INFO("KintonArmDriverNode::arm_joint_pos_callback: New Message Received"); 00078 00079 //use appropiate mutex to shared variables if necessary 00080 this->driver_.lock(); 00081 //this->arm_joint_pos_mutex_.enter(); 00082 00083 //std::cout << msg->data << std::endl; 00084 00085 this->new_pos_.clear(); 00086 this->new_pos_.push_back(msg->position[0]); 00087 this->new_pos_.push_back(msg->position[1]); 00088 this->new_pos_.push_back(msg->position[2]); 00089 this->new_pos_.push_back(msg->position[3]); 00090 this->new_pos_.push_back(msg->position[4]); 00091 00092 //unlock previously blocked shared variables 00093 this->driver_.unlock(); 00094 //this->arm_joint_pos_mutex_.exit(); 00095 } 00096 00097 /* [service callbacks] */ 00098 00099 /* [action callbacks] */ 00100 00101 /* [action requests] */ 00102 00103 void KintonArmDriverNode::postNodeOpenHook(void) 00104 { 00105 } 00106 00107 void KintonArmDriverNode::addNodeDiagnostics(void) 00108 { 00109 } 00110 00111 void KintonArmDriverNode::addNodeOpenedTests(void) 00112 { 00113 } 00114 00115 void KintonArmDriverNode::addNodeStoppedTests(void) 00116 { 00117 } 00118 00119 void KintonArmDriverNode::addNodeRunningTests(void) 00120 { 00121 } 00122 00123 void KintonArmDriverNode::reconfigureNodeHook(int level) 00124 { 00125 // To move the servo positions manually using dynamic reconfigure 00126 00127 this->driver_.lock(); 00128 //this->arm_joint_pos_mutex_.enter(); 00129 00130 this->new_pos_.clear(); 00131 this->new_pos_.push_back(this->driver_.config_.servo_1_pos); 00132 this->new_pos_.push_back(this->driver_.config_.servo_2_pos); 00133 this->new_pos_.push_back(this->driver_.config_.servo_3_pos); 00134 this->new_pos_.push_back(this->driver_.config_.servo_4_pos); 00135 this->new_pos_.push_back(this->driver_.config_.servo_5_pos); 00136 00137 this->driver_.unlock(); 00138 //this->arm_joint_pos_mutex_.exit(); 00139 } 00140 00141 KintonArmDriverNode::~KintonArmDriverNode(void) 00142 { 00143 // [free dynamic memory] 00144 } 00145 00146 /* main function */ 00147 int main(int argc,char *argv[]) 00148 { 00149 return driver_base::main<KintonArmDriverNode>(argc, argv, "kinton_arm_driver_node"); 00150 }