Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <algorithm>
00039
00040
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
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
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
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
00119 errors_ = JointErrorList(joints_.size());
00120 ref_pos_ = JointPosList(joints_.size());
00121 lookup_ = JointStateToCmd(joints_.size());
00122
00123
00124 sub_command_ = node_.subscribe("command", 1, &JointGroupPositionController::commandCB, this);
00125
00126 return true;
00127 }
00128
00129 void JointGroupPositionController::starting()
00130 {
00131
00132 for (size_t i = 0; i < pids_.size(); ++i) {pids_[i].reset();}
00133
00134
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
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
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
00158 {
00159 errors_[i] = joints_[i]->position_ - ref_pos_[i];
00160 }
00161
00162
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
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
00196 for(size_t i = 0; i < joints_.size(); ++i)
00197 {
00198 ref_pos_[i] = command->position[lookup_[i]];
00199 }
00200 }
00201
00202 }