$search
00001 /* 00002 * Software License Agreement (Modified BSD License) 00003 * 00004 * Copyright (c) 2011, PAL Robotics, S.L. 00005 * Copyright (c) 2008, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of PAL Robotics, S.L. nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 */ 00035 00036 00037 // C++ standard headers 00038 #include <algorithm> 00039 00040 // ROS headers 00041 #include "joint_group_position_controller/joint_group_position_controller.h" 00042 #include "angles/angles.h" 00043 #include "pluginlib/class_list_macros.h" 00044 00045 PLUGINLIB_DECLARE_CLASS(joint_group_position_controller, JointGroupPositionController, controller::JointGroupPositionController, pr2_controller_interface::Controller) 00046 00047 namespace controller 00048 { 00049 00050 using std::size_t; 00051 00052 JointGroupPositionController::JointGroupPositionController() 00053 : robot_(0) 00054 {} 00055 00056 JointGroupPositionController::~JointGroupPositionController() 00057 { 00058 sub_command_.shutdown(); 00059 } 00060 00061 bool JointGroupPositionController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) 00062 { 00063 using namespace XmlRpc; 00064 node_ = n; 00065 robot_ = robot; 00066 00067 // Gets all of the joints 00068 XmlRpc::XmlRpcValue joint_names; 00069 if (!node_.getParam("joints", joint_names)) 00070 { 00071 ROS_ERROR("No joints given. (namespace: %s)", node_.getNamespace().c_str()); 00072 return false; 00073 } 00074 if (joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray) 00075 { 00076 ROS_ERROR("Malformed joint specification. (namespace: %s)", node_.getNamespace().c_str()); 00077 return false; 00078 } 00079 for (int i = 0; i < joint_names.size(); ++i) 00080 { 00081 XmlRpcValue &name_value = joint_names[i]; 00082 if (name_value.getType() != XmlRpcValue::TypeString) 00083 { 00084 ROS_ERROR("Array of joint names should contain all strings. (namespace: %s)", 00085 node_.getNamespace().c_str()); 00086 return false; 00087 } 00088 00089 pr2_mechanism_model::JointState *j = robot->getJointState((std::string)name_value); 00090 if (!j) { 00091 ROS_ERROR("Joint not found: %s. (namespace: %s)", 00092 ((std::string)name_value).c_str(), node_.getNamespace().c_str()); 00093 return false; 00094 } 00095 joints_.push_back(j); 00096 } 00097 00098 // Ensures that all the joints are calibrated 00099 for (size_t i = 0; i < joints_.size(); ++i) 00100 { 00101 if (!joints_[i]->calibrated_) 00102 { 00103 ROS_ERROR("Joint %s was not calibrated (namespace: %s)", 00104 joints_[i]->joint_->name.c_str(), node_.getNamespace().c_str()); 00105 return false; 00106 } 00107 } 00108 00109 // Sets up pid controllers for all of the joints 00110 std::string gains_ns; 00111 if (!node_.getParam("gains", gains_ns)) {gains_ns = node_.getNamespace() + "/gains";} 00112 pids_.resize(joints_.size()); 00113 for (size_t i = 0; i < joints_.size(); ++i) 00114 { 00115 if (!pids_[i].init(ros::NodeHandle(gains_ns + "/" + joints_[i]->joint_->name))) {return false;} 00116 } 00117 00118 // Preallocate resources 00119 errors_ = JointErrorList(joints_.size()); 00120 ref_pos_ = JointPosList(joints_.size()); 00121 lookup_ = JointStateToCmd(joints_.size()); 00122 00123 // Create input topic subscriptor 00124 sub_command_ = node_.subscribe("command", 1, &JointGroupPositionController::commandCB, this); 00125 00126 return true; 00127 } 00128 00129 void JointGroupPositionController::starting() 00130 { 00131 // Reset PIDs 00132 for (size_t i = 0; i < pids_.size(); ++i) {pids_[i].reset();} 00133 00134 // Cache time and joint positions 00135 last_time_ = robot_->getTime(); 00136 for (size_t i = 0; i < joints_.size(); ++i) {ref_pos_[i] = joints_[i]->position_;} 00137 } 00138 00139 void JointGroupPositionController::update() 00140 { 00141 // Compute delta time and update time cache 00142 ros::Time time = robot_->getTime(); 00143 ros::Duration dt = time - last_time_; 00144 last_time_ = time; 00145 00146 for(size_t i = 0; i < joints_.size(); ++i) 00147 { 00148 // Tracking error 00149 if(joints_[i]->joint_->type == urdf::Joint::REVOLUTE) 00150 { 00151 angles::shortest_angular_distance_with_limits(ref_pos_[i], joints_[i]->position_, joints_[i]->joint_->limits->lower, joints_[i]->joint_->limits->upper, errors_[i]); 00152 } 00153 else if(joints_[i]->joint_->type == urdf::Joint::CONTINUOUS) 00154 { 00155 errors_[i] = angles::shortest_angular_distance(ref_pos_[i], joints_[i]->position_); 00156 } 00157 else // Prismatic 00158 { 00159 errors_[i] = joints_[i]->position_ - ref_pos_[i]; 00160 } 00161 00162 // Commanded effort 00163 joints_[i]->commanded_effort_ = pids_[i].updatePid(errors_[i], dt); 00164 } 00165 } 00166 00167 void JointGroupPositionController::commandCB(const sensor_msgs::JointState::ConstPtr &command) 00168 { 00169 if (command->name.size() != command->position.size()) 00170 { 00171 ROS_ERROR("Size mismatch in members of input command (name, position)."); 00172 return; 00173 } 00174 00175 // Map the controlled joints to the joints in the message 00176 lookup_ = JointStateToCmd(lookup_.size(), -1); 00177 for(size_t i = 0; i < joints_.size(); ++i) 00178 { 00179 for (size_t j = 0; j < command->name.size(); ++j) 00180 { 00181 if (command->name[j] == joints_[i]->joint_->name) 00182 { 00183 lookup_[i] = j; 00184 break; 00185 } 00186 } 00187 00188 if (lookup_[i] == -1) 00189 { 00190 ROS_ERROR_STREAM("Unable to locate joint " << joints_[i]->joint_->name << " in the commanded trajectory."); 00191 return; 00192 } 00193 } 00194 00195 // Populate reference position vector 00196 for(size_t i = 0; i < joints_.size(); ++i) 00197 { 00198 ref_pos_[i] = command->position[lookup_[i]]; 00199 } 00200 } 00201 00202 } // controller