$search
00001 00013 /************************************************************************ 00014 * Copyright (C) 2012 Eindhoven University of Technology (TU/e). * 00015 * All rights reserved. * 00016 ************************************************************************ 00017 * Redistribution and use in source and binary forms, with or without * 00018 * modification, are permitted provided that the following conditions * 00019 * are met: * 00020 * * 00021 * 1. Redistributions of source code must retain the above * 00022 * copyright notice, this list of conditions and the following * 00023 * disclaimer. * 00024 * * 00025 * 2. Redistributions in binary form must reproduce the above * 00026 * copyright notice, this list of conditions and the following * 00027 * disclaimer in the documentation and/or other materials * 00028 * provided with the distribution. * 00029 * * 00030 * THIS SOFTWARE IS PROVIDED BY TU/e "AS IS" AND ANY EXPRESS OR * 00031 * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * 00032 * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * 00033 * ARE DISCLAIMED. IN NO EVENT SHALL TU/e OR CONTRIBUTORS BE LIABLE * 00034 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * 00035 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT * 00036 * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; * 00037 * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF * 00038 * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * 00039 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE * 00040 * USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH * 00041 * DAMAGE. * 00042 * * 00043 * The views and conclusions contained in the software and * 00044 * documentation are those of the authors and should not be * 00045 * interpreted as representing official policies, either expressed or * 00046 * implied, of TU/e. * 00047 ************************************************************************/ 00048 00049 00050 #include "tulip_controller.h" 00051 #include <pluginlib/class_list_macros.h> 00052 #include "tulip_controller_functions.cpp" 00053 00054 // http://www.ros.org/wiki/pr2_mechanism 00055 // http://www.ros.org/wiki/pr2_mechanism/Tutorials 00056 00057 00058 00059 #define ENABLE_BACKLASH false 00060 00061 namespace tulip_controller_namespace { 00062 00063 00065 bool tulip_controller_class::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) 00066 { 00067 ROS_INFO("tulip_controller::init()"); 00068 joint_pos_current.resize(17); 00069 joint_pos_desired.resize(17); 00070 joint_pos_feedback.resize(17); 00071 joint_pos_init.resize(17); 00072 joint_state.resize(17); 00073 backlash_state.resize(17); 00074 joint_name.resize(17); 00075 pid_controller.resize(17); 00076 published_jointdata = false; 00077 00078 exp.resize(1); 00079 00080 //NOTE: the zeroth element of all joint vectors is not used 00081 // -to keep compatible with matlab, where there is no zeroth element in a vector 00082 // -to use the conventional joint numbering of TUlip, 00083 00084 joint_name[0] = ""; 00085 joint_name[1] = "right_hip_yaw"; 00086 joint_name[2] = "right_hip_roll"; 00087 joint_name[3] = "right_hip_pitch"; 00088 joint_name[4] = "right_knee_pitch"; 00089 joint_name[5] = "right_ankle_pitch"; 00090 joint_name[6] = "right_ankle_roll"; 00091 joint_name[7] = "left_hip_yaw"; 00092 joint_name[8] = "left_hip_roll"; 00093 joint_name[9] = "left_hip_pitch"; 00094 joint_name[10] = "left_knee_pitch"; 00095 joint_name[11] = "left_ankle_pitch"; 00096 joint_name[12] = "left_ankle_roll"; 00097 joint_name[13] = "neck_pitch"; 00098 joint_name[14] = "neck_yaw"; 00099 joint_name[15] = "right_shoulder_pitch"; 00100 joint_name[16] = "left_shoulder_pitch"; 00101 00102 //get joints and controller from parameter server 00103 for (int i = 1; i < 17 ; i++){ // for loop starts at i=1, not i=0 00104 00105 joint_state[i] = robot->getJointState(joint_name[i]); 00106 if (!joint_state[i] || 00107 !pid_controller[i].init(ros::NodeHandle(n, joint_name[i] + "_pid")) || 00108 !n.getParam(joint_name[i] + "_pid/r", joint_pos_init[i])) 00109 { 00110 ROS_ERROR("Error reading joint parameters, check for typos in yaml file"); 00111 while(1){}; 00112 } 00113 } 00114 00115 if (ENABLE_BACKLASH) { 00116 //get backlash joints 00117 for (int i = 1; i < 17 ; i++){ // for loop starts at i=1, not i=0 00118 backlash_state[i] = robot->getJointState(joint_name[i] + "_backlash"); 00119 if (backlash_state[i]) 00120 { 00121 ROS_INFO("Backlash defined in urdf model for %s",joint_name[i].c_str()); 00122 } 00123 } 00124 } 00125 00126 //get initial model state from parameter server 00127 00128 if (!getExpPar("home_posture", exp[0], n)) 00129 { 00130 ROS_ERROR("Error reading experiment parameters, check for typos in yaml file"); 00131 while(1){}; 00132 } 00133 00134 00135 std::cout << "Succesfully read parameters" << std::endl; 00136 00137 joint_state_pub_ = n.advertise<tulip_gazebo::joint_state_message>("matlab_joints", StoreLen); 00138 storage_index_ = 0; // start recording immediately, set to StoreLen to start recording when triggered by capture 00139 cycle_index_ = 0; 00140 00141 // copy robot pointer so we can access time 00142 robot_ = robot; 00143 00144 //set initial posture 00145 ros::service::waitForService("/gazebo/set_model_configuration"); 00146 ros::ServiceClient client_initpose = n.serviceClient<gazebo_msgs::SetModelConfiguration>("/gazebo/set_model_configuration"); 00147 gazebo_msgs::SetModelConfiguration srv_initpose; 00148 00149 srv_initpose.request.model_name = "tulip"; // model to set state 00150 srv_initpose.request.urdf_param_name = "robot_description"; // parameter name that contains the urdf XML. 00151 srv_initpose.request.joint_names = joint_name; 00152 srv_initpose.request.joint_positions = joint_pos_init; 00153 00154 if (client_initpose.call(srv_initpose)) 00155 { ROS_INFO("Succesfully set initial posture to "); 00156 for (int i=1; i<17; i++) {std::cout << joint_pos_init[i] << " ";} 00157 std::cout << std::endl; 00158 } 00159 else 00160 { ROS_ERROR("Failed to set initial posture: %s",srv_initpose.response.status_message.c_str()); } 00161 00162 //unpause physics 00163 ros::service::waitForService("/gazebo/unpause_physics"); 00164 ros::ServiceClient client_unpause = n.serviceClient<std_srvs::Empty>("/gazebo/unpause_physics"); 00165 std_srvs::Empty srv_unpause; 00166 00167 if (client_unpause.call(srv_unpause)) { 00168 ROS_INFO("Succesfully unpaused physics"); 00169 } else { 00170 ROS_ERROR("Failed to unpause physics"); 00171 } 00172 00173 return true; 00174 } 00175 00177 void tulip_controller_class::starting() 00178 { 00179 ROS_INFO("tulip_controller::starting()"); 00180 for (int i = 1; i < 17; i++){ 00181 joint_pos_init[i] = joint_state[i]->position_; 00182 pid_controller[i].reset(); 00183 } 00184 time_of_first_cycle_ = robot_->getTime(); 00185 time_of_previous_cycle_ = robot_->getTime(); 00186 00187 //http://answers.ros.org/question/2009/applying-a-force-to-a-rigid-body 00188 //https://code.ros.org/svn/wg-ros-pkg/stacks/wg_robots_gazebo/trunk/pr2_arm_gazebo/src/move_arm.cpp 00189 //http://www.ros.org/wiki/ROS/Tutorials/WritingServiceClient(c%2B%2B) 00190 ROS_INFO("time is push time!"); 00191 00192 // give push prescribed in yaml parameter file 00193 00194 00195 ros::NodeHandle n; 00196 gazebo_msgs::ApplyBodyWrench srv_wrench; 00197 srv_wrench.request.wrench.force.x = exp[0].push.force.x; 00198 srv_wrench.request.wrench.force.y = exp[0].push.force.y; 00199 srv_wrench.request.wrench.force.z = exp[0].push.force.z; 00200 srv_wrench.request.start_time = robot_->getTime() + ros::Duration(exp[0].push.time); 00201 srv_wrench.request.duration = ros::Duration(exp[0].push.duration); 00202 00203 tulip_controller_class::applyForcetoRobot(srv_wrench, n); 00204 } 00205 00206 00208 void tulip_controller_class::update() 00209 { 00210 ros::NodeHandle n; 00211 //ROS_INFO("tulip_controller::update()"); 00212 00213 ros::Duration dt = robot_->getTime() - time_of_previous_cycle_; 00214 time_of_previous_cycle_ = robot_->getTime(); 00215 00216 for (int i = 1; i < 17; i++){ 00217 joint_pos_desired[i] = joint_pos_init[i]; 00218 if (ENABLE_BACKLASH) { joint_pos_current[i] = joint_state[i]->position_ + tulip_controller_class::getBacklashPosition(backlash_state,i); 00219 } else { joint_pos_current[i] = joint_state[i]->position_;} 00220 joint_pos_feedback[i] = pid_controller[i].updatePid(joint_pos_current[i]-joint_pos_desired[i], dt); 00221 joint_state[i]->commanded_effort_ = joint_pos_feedback[i]; 00222 00223 //ROS_INFO("joint[%2d] %-20s desired %f \tcurrent %f \teffort %f",i,joint_name[i].c_str(),joint_pos_desired[i],joint_pos_current[i],joint_pos_feedback[i]); 00224 } 00225 00226 00227 cycle_index_ = cycle_index_ + 1; 00228 if (cycle_index_ % 10 == 1) { //only save every tenth cycle 00229 for (int i = 1; i < 17; i++){ 00230 int index = storage_index_; 00231 if ((index >= 0) && (index < StoreLen)) 00232 { 00233 storage_[index].cycle_nr = (cycle_index_-1)/10 +1; //trick to count 1,2,3,4 instead of 1,11,21,31 because we only save every tenth cycle 00234 storage_[index].time = robot_->getTime().toSec(); 00235 storage_[index].joint_nr = i; 00236 storage_[index].desired_position = joint_pos_desired[i]; 00237 if (ENABLE_BACKLASH) { 00238 storage_[index].position = joint_state[i]->position_ + tulip_controller_class::getBacklashPosition(backlash_state,i); 00239 storage_[index].velocity = joint_state[i]->velocity_ + tulip_controller_class::getBacklashVelocity(backlash_state,i); 00240 } else { 00241 storage_[index].position = joint_state[i]->position_; 00242 storage_[index].velocity = joint_state[i]->velocity_; 00243 } 00244 storage_[index].commanded_effort = joint_state[i]->commanded_effort_; 00245 storage_[index].measured_effort = joint_state[i]->measured_effort_; 00246 00247 // Increment for the next cycle. 00248 storage_index_ = index+1; 00249 } 00250 00251 } 00252 if (storage_index_ >= StoreLen && !published_jointdata) { 00253 tulip_controller_class::capture(); 00254 published_jointdata = true; 00255 } 00256 } 00257 } 00258 00259 00261 void tulip_controller_class::stopping() 00262 {} 00263 00265 bool tulip_controller_class::capture() 00266 { 00267 /* Record the starting time. */ 00268 ros::Time started = ros::Time::now(); 00269 00270 /* Now wait until the buffer is full. */ 00271 while (storage_index_ < StoreLen) 00272 { 00273 /* Sleep for 1ms as not to hog the CPU. */ 00274 ros::Duration(0.001).sleep(); 00275 00276 /* Make sure we don't hang here forever. */ 00277 if (ros::Time::now() - started > ros::Duration(20.0)) 00278 { 00279 ROS_ERROR("Waiting for buffer to fill up took longer than 20 seconds!"); 00280 return false; 00281 } 00282 } 00283 00284 /* Then we can publish the buffer contents. */ 00285 int index; 00286 for (index = 0 ; index < StoreLen ; index++) 00287 joint_state_pub_.publish(storage_[index]); 00288 00289 ROS_INFO("Published joint data"); 00290 return true; 00291 } 00292 00293 } // namespace 00294 00296 PLUGINLIB_DECLARE_CLASS(tulip_controller,tulip_controller_plugin, 00297 tulip_controller_namespace::tulip_controller_class, 00298 pr2_controller_interface::Controller)