00001
00027 #include "sr_mechanism_controllers/srh_joint_velocity_controller.hpp"
00028 #include "angles/angles.h"
00029 #include "pluginlib/class_list_macros.h"
00030 #include <sstream>
00031 #include <math.h>
00032 #include "sr_utilities/sr_math_utils.hpp"
00033
00034 #include <std_msgs/Float64.h>
00035
00036 PLUGINLIB_EXPORT_CLASS(controller::SrhJointVelocityController, controller_interface::ControllerBase)
00037
00038 using namespace std;
00039
00040 namespace controller
00041 {
00042
00043 SrhJointVelocityController::SrhJointVelocityController()
00044 : velocity_deadband(0.015)
00045 {
00046 }
00047
00048 bool SrhJointVelocityController::init(ros_ethercat_model::RobotState *robot, ros::NodeHandle &n)
00049 {
00050 ROS_ASSERT(robot);
00051 robot_ = robot;
00052 node_ = n;
00053
00054 if (!node_.getParam("joint", joint_name_))
00055 {
00056 ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
00057 return false;
00058 }
00059
00060 pid_controller_velocity_.reset(new control_toolbox::Pid());
00061 if (!pid_controller_velocity_->init(ros::NodeHandle(node_, "pid")))
00062 return false;
00063
00064 controller_state_publisher_.reset(new realtime_tools::RealtimePublisher<control_msgs::JointControllerState>
00065 (node_, "state", 1));
00066
00067 ROS_DEBUG(" --------- ");
00068 ROS_DEBUG_STREAM("Init: " << joint_name_);
00069
00070
00071 has_j2 = is_joint_0();
00072 if (has_j2)
00073 {
00074 get_joints_states_1_2();
00075 if (!joint_state_)
00076 {
00077 ROS_ERROR("SrhVelocityController could not find the first joint relevant to \"%s\"\n", joint_name_.c_str());
00078 return false;
00079 }
00080 if (!joint_state_2)
00081 {
00082 ROS_ERROR("SrhVelocityController could not find the second joint relevant to \"%s\"\n", joint_name_.c_str());
00083 return false;
00084 }
00085 if (!joint_state_2->calibrated_)
00086 {
00087 ROS_ERROR("Joint %s not calibrated for SrhVelocityController", joint_name_.c_str());
00088 return false;
00089 }
00090 else
00091 joint_state_->calibrated_ = true;
00092 }
00093 else
00094 {
00095 joint_state_ = robot_->getJointState(joint_name_);
00096 if (!joint_state_)
00097 {
00098 ROS_ERROR("SrhVelocityController could not find joint named \"%s\"\n", joint_name_.c_str());
00099 return false;
00100 }
00101 if (!joint_state_->calibrated_)
00102 {
00103 ROS_ERROR("Joint %s not calibrated for SrhJointVelocityController", joint_name_.c_str());
00104 return false;
00105 }
00106 }
00107
00108 friction_compensator.reset(new sr_friction_compensation::SrFrictionCompensator(joint_name_));
00109
00110 serve_set_gains_ = node_.advertiseService("set_gains", &SrhJointVelocityController::setGains, this);
00111 serve_reset_gains_ = node_.advertiseService("reset_gains", &SrhJointVelocityController::resetGains, this);
00112
00113 after_init();
00114 return true;
00115 }
00116
00117 void SrhJointVelocityController::starting(const ros::Time& time)
00118 {
00119 resetJointState();
00120 pid_controller_velocity_->reset();
00121 read_parameters();
00122
00123 if (has_j2)
00124 ROS_WARN_STREAM("Reseting PID for joints " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
00125 else
00126 ROS_WARN_STREAM("Reseting PID for joint " << joint_state_->joint_->name);
00127 }
00128
00129 bool SrhJointVelocityController::setGains(sr_robot_msgs::SetPidGains::Request &req,
00130 sr_robot_msgs::SetPidGains::Response &resp)
00131 {
00132 pid_controller_velocity_->setGains(req.p, req.i, req.d, req.i_clamp, -req.i_clamp);
00133 max_force_demand = req.max_force;
00134 friction_deadband = req.friction_deadband;
00135 velocity_deadband = req.deadband;
00136
00137
00138 node_.setParam("pid/p", req.p);
00139 node_.setParam("pid/i", req.i);
00140 node_.setParam("pid/d", req.d);
00141 node_.setParam("pid/i_clamp", req.i_clamp);
00142
00143 node_.setParam("pid/max_force", max_force_demand);
00144 node_.setParam("pid/velocity_deadband", velocity_deadband);
00145 node_.setParam("pid/friction_deadband", friction_deadband);
00146
00147 return true;
00148 }
00149
00150 bool SrhJointVelocityController::resetGains(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp)
00151 {
00152 resetJointState();
00153
00154 if (!pid_controller_velocity_->init(ros::NodeHandle(node_, "velocity_pid")))
00155 return false;
00156
00157 read_parameters();
00158
00159 if (has_j2)
00160 ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
00161 else
00162 ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name);
00163
00164 return true;
00165 }
00166
00167 void SrhJointVelocityController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
00168 {
00169 pid_controller_velocity_->getGains(p, i, d, i_max, i_min);
00170 }
00171
00172 void SrhJointVelocityController::update(const ros::Time& time, const ros::Duration& period)
00173 {
00174 if (!has_j2 && !joint_state_->calibrated_)
00175 return;
00176
00177 ROS_ASSERT(robot_);
00178 ROS_ASSERT(joint_state_->joint_);
00179
00180 if (!initialized_)
00181 {
00182 resetJointState();
00183 initialized_ = true;
00184 }
00185 if (has_j2)
00186 command_ = joint_state_->commanded_velocity_ + joint_state_2->commanded_velocity_;
00187 else
00188 command_ = joint_state_->commanded_velocity_;
00189 command_ = clamp_command(command_);
00190
00191
00192 double error_velocity = 0.0;
00193 if (has_j2)
00194 error_velocity = (joint_state_->velocity_ + joint_state_2->velocity_) - command_;
00195 else
00196 error_velocity = joint_state_->velocity_ - command_;
00197
00198 double commanded_effort = 0.0;
00199
00200
00201 if (!hysteresis_deadband.is_in_deadband(command_, error_velocity, velocity_deadband))
00202 {
00203 commanded_effort = pid_controller_velocity_->computeCommand(-error_velocity, period);
00204
00205
00206 commanded_effort = min(commanded_effort, (max_force_demand * max_force_factor_));
00207 commanded_effort = max(commanded_effort, -(max_force_demand * max_force_factor_));
00208
00209 if (has_j2)
00210 commanded_effort += friction_compensator->friction_compensation((joint_state_->position_ + joint_state_2->position_),
00211 (joint_state_->velocity_ + joint_state_2->velocity_),
00212 int(commanded_effort),
00213 friction_deadband);
00214 else
00215 commanded_effort += friction_compensator->friction_compensation(joint_state_->position_,
00216 joint_state_->velocity_,
00217 int(commanded_effort),
00218 friction_deadband);
00219 }
00220
00221 joint_state_->commanded_effort_ = commanded_effort;
00222
00223 if (loop_count_ % 10 == 0)
00224 {
00225 if (controller_state_publisher_ && controller_state_publisher_->trylock())
00226 {
00227 controller_state_publisher_->msg_.header.stamp = time;
00228 controller_state_publisher_->msg_.set_point = command_;
00229 if (has_j2)
00230 controller_state_publisher_->msg_.process_value = joint_state_->velocity_ + joint_state_2->velocity_;
00231 else
00232 controller_state_publisher_->msg_.process_value = joint_state_->velocity_;
00233 controller_state_publisher_->msg_.error = error_velocity;
00234 controller_state_publisher_->msg_.time_step = period.toSec();
00235 controller_state_publisher_->msg_.command = commanded_effort;
00236
00237 double dummy;
00238 getGains(controller_state_publisher_->msg_.p,
00239 controller_state_publisher_->msg_.i,
00240 controller_state_publisher_->msg_.d,
00241 controller_state_publisher_->msg_.i_clamp,
00242 dummy);
00243 controller_state_publisher_->unlockAndPublish();
00244 }
00245 }
00246 loop_count_++;
00247 }
00248
00249 void SrhJointVelocityController::read_parameters()
00250 {
00251 node_.param<double>("pid/max_force", max_force_demand, 1023.0);
00252 node_.param<double>("pid/velocity_deadband", velocity_deadband, 0.015);
00253 node_.param<int>("pid/friction_deadband", friction_deadband, 5);
00254 }
00255
00256 void SrhJointVelocityController::setCommandCB(const std_msgs::Float64ConstPtr& msg)
00257 {
00258 joint_state_->commanded_velocity_ = msg->data;
00259 if (has_j2)
00260 joint_state_2->commanded_velocity_ = 0.0;
00261 }
00262
00263 void SrhJointVelocityController::resetJointState()
00264 {
00265 if (has_j2)
00266 {
00267 joint_state_->commanded_velocity_ = joint_state_->velocity_;
00268 joint_state_2->commanded_velocity_ = joint_state_2->velocity_;
00269 command_ = joint_state_->velocity_ + joint_state_2->velocity_;
00270 }
00271 else
00272 {
00273 joint_state_->commanded_velocity_ = joint_state_->velocity_;
00274 command_ = joint_state_->velocity_;
00275 }
00276 }
00277 }
00278
00279
00280
00281
00282
00283
00284
00285