|
| 1 | +/********************************************************************* |
| 2 | + * Software License Agreement (BSD License) |
| 3 | + * |
| 4 | + * Copyright (c) 2008, Willow Garage, Inc. |
| 5 | + * All rights reserved. |
| 6 | + * |
| 7 | + * Redistribution and use in source and binary forms, with or without |
| 8 | + * modification, are permitted provided that the following conditions |
| 9 | + * are met: |
| 10 | + * |
| 11 | + * * Redistributions of source code must retain the above copyright |
| 12 | + * notice, this list of conditions and the following disclaimer. |
| 13 | + * * Redistributions in binary form must reproduce the above |
| 14 | + * copyright notice, this list of conditions and the following |
| 15 | + * disclaimer in the documentation and/or other materials provided |
| 16 | + * with the distribution. |
| 17 | + * * Neither the name of the Willow Garage nor the names of its |
| 18 | + * contributors may be used to endorse or promote products derived |
| 19 | + * from this software without specific prior written permission. |
| 20 | + * |
| 21 | + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
| 22 | + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
| 23 | + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
| 24 | + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
| 25 | + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
| 26 | + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
| 27 | + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; |
| 28 | + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER |
| 29 | + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
| 30 | + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
| 31 | + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
| 32 | + * POSSIBILITY OF SUCH DAMAGE. |
| 33 | + *********************************************************************/ |
| 34 | + |
| 35 | +#include "robot_mechanism_controllers/joint_group_velocity_controller.h" |
| 36 | +#include "pluginlib/class_list_macros.h" |
| 37 | + |
| 38 | +PLUGINLIB_EXPORT_CLASS( controller::JointGroupVelocityController, pr2_controller_interface::Controller) |
| 39 | + |
| 40 | +using namespace std; |
| 41 | + |
| 42 | +namespace controller { |
| 43 | + |
| 44 | +JointGroupVelocityController::JointGroupVelocityController() |
| 45 | +: robot_(NULL), loop_count_(0) |
| 46 | +{ |
| 47 | +} |
| 48 | + |
| 49 | +JointGroupVelocityController::~JointGroupVelocityController() |
| 50 | +{ |
| 51 | + sub_command_.shutdown(); |
| 52 | +} |
| 53 | + |
| 54 | +bool JointGroupVelocityController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
| 55 | +{ |
| 56 | + using namespace XmlRpc; |
| 57 | + assert(robot); |
| 58 | + node_ = n; |
| 59 | + robot_ = robot; |
| 60 | + |
| 61 | + // Gets all of the joints |
| 62 | + XmlRpc::XmlRpcValue joint_names; |
| 63 | + if (!node_.getParam("joints", joint_names)) |
| 64 | + { |
| 65 | + ROS_ERROR("No joints given. (namespace: %s)", node_.getNamespace().c_str()); |
| 66 | + return false; |
| 67 | + } |
| 68 | + if (joint_names.getType() != XmlRpc::XmlRpcValue::TypeArray) |
| 69 | + { |
| 70 | + ROS_ERROR("Malformed joint specification. (namespace: %s)", node_.getNamespace().c_str()); |
| 71 | + return false; |
| 72 | + } |
| 73 | + for (int i = 0; i < joint_names.size(); ++i) |
| 74 | + { |
| 75 | + XmlRpcValue &name_value = joint_names[i]; |
| 76 | + if (name_value.getType() != XmlRpcValue::TypeString) |
| 77 | + { |
| 78 | + ROS_ERROR("Array of joint names should contain all strings. (namespace: %s)", |
| 79 | + node_.getNamespace().c_str()); |
| 80 | + return false; |
| 81 | + } |
| 82 | + |
| 83 | + pr2_mechanism_model::JointState *j = robot->getJointState((std::string)name_value); |
| 84 | + if (!j) { |
| 85 | + ROS_ERROR("Joint not found: %s. (namespace: %s)", |
| 86 | + ((std::string)name_value).c_str(), node_.getNamespace().c_str()); |
| 87 | + return false; |
| 88 | + } |
| 89 | + joints_.push_back(j); |
| 90 | + } |
| 91 | + |
| 92 | + // Sets up pid controllers for all of the joints |
| 93 | + std::string gains_ns; |
| 94 | + if (!node_.getParam("gains", gains_ns)) |
| 95 | + gains_ns = node_.getNamespace() + "/gains"; |
| 96 | + pid_controllers_.resize(joints_.size()); |
| 97 | + for (size_t i = 0; i < joints_.size(); ++i) |
| 98 | + { |
| 99 | + ros::NodeHandle joint_nh(gains_ns + "/" + joints_[i]->joint_->name); |
| 100 | + if (!pid_controllers_[i].init(joint_nh)) |
| 101 | + return false; |
| 102 | + } |
| 103 | + |
| 104 | + n_joints_ = joint_names.size(); |
| 105 | + |
| 106 | + commands_buffer_.writeFromNonRT(std::vector<double>(n_joints_, 0.0)); |
| 107 | + |
| 108 | + controller_state_publisher_.reset( |
| 109 | + new realtime_tools::RealtimePublisher<pr2_controllers_msgs::JointControllerStateArray> |
| 110 | + (node_, "statearray", 1)); |
| 111 | + controller_state_publisher_->lock(); |
| 112 | + controller_state_publisher_->msg_.controllestate.resize(joints_.size()); |
| 113 | + controller_state_publisher_->unlock(); |
| 114 | + |
| 115 | + sub_command_ = node_.subscribe<std_msgs::Float64MultiArray>("command", 1, &JointGroupVelocityController::setCommandCB, this); |
| 116 | + |
| 117 | + return true; |
| 118 | +} |
| 119 | + |
| 120 | +void JointGroupVelocityController::getGains(control_toolbox::Pid &pid, double &p, double &i, double &d, double &i_max, double &i_min) |
| 121 | +{ |
| 122 | + pid.getGains(p,i,d,i_max,i_min); |
| 123 | +} |
| 124 | + |
| 125 | +std::vector< std::string > JointGroupVelocityController::getJointName() |
| 126 | +{ |
| 127 | + std::vector< std::string > joint_names; |
| 128 | + for(unsigned int i=0; i<n_joints_; i++) |
| 129 | + { |
| 130 | + joint_names.push_back(joints_[i]->joint_->name); |
| 131 | + } |
| 132 | + return joint_names; |
| 133 | +} |
| 134 | + |
| 135 | +// Set the joint velocity commands |
| 136 | +void JointGroupVelocityController::setCommand(std::vector<double> cmd) |
| 137 | +{ |
| 138 | + commands_buffer_.writeFromNonRT(cmd); |
| 139 | +} |
| 140 | + |
| 141 | +// Return the current velocity commands |
| 142 | +void JointGroupVelocityController::getCommand(std::vector<double> & cmd) |
| 143 | +{ |
| 144 | + cmd = *commands_buffer_.readFromRT(); |
| 145 | +} |
| 146 | + |
| 147 | +void JointGroupVelocityController::starting() |
| 148 | +{ |
| 149 | + for (size_t i = 0; i < pid_controllers_.size(); ++i) |
| 150 | + pid_controllers_[i].reset(); |
| 151 | + |
| 152 | +} |
| 153 | +void JointGroupVelocityController::update() |
| 154 | +{ |
| 155 | + assert(robot_ != NULL); |
| 156 | + ros::Time time = robot_->getTime(); |
| 157 | + ros::Duration dt_ = time - last_time_; |
| 158 | + std::vector<double> & commands = *commands_buffer_.readFromRT(); |
| 159 | + std::vector<double> compute_command(n_joints_); |
| 160 | + std::vector<double> compute_error(n_joints_); |
| 161 | + |
| 162 | + for(unsigned int i=0; i<n_joints_; i++) |
| 163 | + { |
| 164 | + compute_error[i] = commands[i] - joints_[i]->velocity_; |
| 165 | + double command = pid_controllers_[i].computeCommand(compute_error[i], dt_); |
| 166 | + joints_[i]->commanded_effort_ += command; |
| 167 | + compute_command[i] = command; |
| 168 | + } |
| 169 | + |
| 170 | + if(loop_count_ % 10 == 0){ |
| 171 | + if(controller_state_publisher_ && controller_state_publisher_->trylock()) |
| 172 | + { |
| 173 | + controller_state_publisher_->msg_.header.stamp = time; |
| 174 | + for (unsigned int i = 0; i < n_joints_; ++i) |
| 175 | + { |
| 176 | + pr2_controllers_msgs::JointControllerState singlejointcontrollerstate; |
| 177 | + singlejointcontrollerstate.header.stamp = time; |
| 178 | + singlejointcontrollerstate.set_point = commands[i]; |
| 179 | + singlejointcontrollerstate.process_value = joints_[i]->velocity_; |
| 180 | + singlejointcontrollerstate.error = compute_error[i]; |
| 181 | + singlejointcontrollerstate.time_step = dt_.toSec(); |
| 182 | + singlejointcontrollerstate.command = compute_command[i]; |
| 183 | + |
| 184 | + double dummy; |
| 185 | + getGains(pid_controllers_[i], |
| 186 | + singlejointcontrollerstate.p, |
| 187 | + singlejointcontrollerstate.i, |
| 188 | + singlejointcontrollerstate.d, |
| 189 | + singlejointcontrollerstate.i_clamp, |
| 190 | + dummy); |
| 191 | + controller_state_publisher_->msg_.controllestate.push_back(singlejointcontrollerstate); |
| 192 | + } |
| 193 | + controller_state_publisher_->unlockAndPublish(); |
| 194 | + } |
| 195 | +} |
| 196 | + |
| 197 | + loop_count_++; |
| 198 | + |
| 199 | + last_time_ = time; |
| 200 | +} |
| 201 | + |
| 202 | +void JointGroupVelocityController::setCommandCB(const std_msgs::Float64MultiArrayConstPtr& msg) |
| 203 | +{ |
| 204 | + // command_ = msg->data; |
| 205 | + if(msg->data.size()!=n_joints_) |
| 206 | + { |
| 207 | + ROS_ERROR_STREAM("Dimension of command (" << msg->data.size() << ") does not match number of joints (" << n_joints_ << ")! Not executing!"); |
| 208 | + return; |
| 209 | + } |
| 210 | + // command_ = msg->data; |
| 211 | + commands_buffer_.writeFromNonRT(msg->data); |
| 212 | +} |
| 213 | + |
| 214 | +} // namespace |
0 commit comments