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
00039
00040
00041
00042
00043 #include <velocity_controllers/joint_position_controller.h>
00044 #include <angles/angles.h>
00045 #include <pluginlib/class_list_macros.h>
00046
00047 namespace velocity_controllers {
00048
00049 JointPositionController::JointPositionController()
00050 : loop_count_(0)
00051 {}
00052
00053 JointPositionController::~JointPositionController()
00054 {
00055 sub_command_.shutdown();
00056 }
00057
00058 bool JointPositionController::init(hardware_interface::VelocityJointInterface *robot, ros::NodeHandle &n)
00059 {
00060
00061 std::string joint_name;
00062 if (!n.getParam("joint", joint_name))
00063 {
00064 ROS_ERROR("No joint given (namespace: %s)", n.getNamespace().c_str());
00065 return false;
00066 }
00067
00068
00069 if (!pid_controller_.init(ros::NodeHandle(n, "pid")))
00070 return false;
00071
00072
00073 controller_state_publisher_.reset(
00074 new realtime_tools::RealtimePublisher<control_msgs::JointControllerState>(n, "state", 1));
00075
00076
00077 sub_command_ = n.subscribe<std_msgs::Float64>("command", 1, &JointPositionController::setCommandCB, this);
00078
00079
00080 joint_ = robot->getHandle(joint_name);
00081
00082
00083 urdf::Model urdf;
00084 if (!urdf.initParam("robot_description"))
00085 {
00086 ROS_ERROR("Failed to parse urdf file");
00087 return false;
00088 }
00089 joint_urdf_ = urdf.getJoint(joint_name);
00090 if (!joint_urdf_)
00091 {
00092 ROS_ERROR("Could not find joint '%s' in urdf", joint_name.c_str());
00093 return false;
00094 }
00095
00096 return true;
00097 }
00098
00099 void JointPositionController::setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
00100 {
00101 pid_controller_.setGains(p,i,d,i_max,i_min);
00102 }
00103
00104 void JointPositionController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
00105 {
00106 pid_controller_.getGains(p,i,d,i_max,i_min);
00107 }
00108
00109 void JointPositionController::printDebug()
00110 {
00111 pid_controller_.printValues();
00112 }
00113
00114 std::string JointPositionController::getJointName()
00115 {
00116 return joint_.getName();
00117 }
00118
00119 double JointPositionController::getPosition()
00120 {
00121 return joint_.getPosition();
00122 }
00123
00124
00125 void JointPositionController::setCommand(double pos_command)
00126 {
00127 command_struct_.position_ = pos_command;
00128 command_struct_.has_velocity_ = false;
00129
00130
00131
00132
00133 command_.writeFromNonRT(command_struct_);
00134 }
00135
00136
00137 void JointPositionController::setCommand(double pos_command, double vel_command)
00138 {
00139 command_struct_.position_ = pos_command;
00140 command_struct_.velocity_ = vel_command;
00141 command_struct_.has_velocity_ = true;
00142
00143 command_.writeFromNonRT(command_struct_);
00144 }
00145
00146 void JointPositionController::starting(const ros::Time& time)
00147 {
00148 double pos_command = joint_.getPosition();
00149
00150
00151 enforceJointLimits(pos_command);
00152
00153 command_struct_.position_ = pos_command;
00154 command_struct_.has_velocity_ = false;
00155
00156 command_.initRT(command_struct_);
00157
00158 pid_controller_.reset();
00159 }
00160
00161 void JointPositionController::update(const ros::Time& time, const ros::Duration& period)
00162 {
00163 command_struct_ = *(command_.readFromRT());
00164 double command_position = command_struct_.position_;
00165 double command_velocity = command_struct_.velocity_;
00166 bool has_velocity_ = command_struct_.has_velocity_;
00167
00168 double error, vel_error;
00169 double commanded_velocity;
00170
00171 double current_position = joint_.getPosition();
00172
00173
00174 enforceJointLimits(command_position);
00175
00176
00177 if (joint_urdf_->type == urdf::Joint::REVOLUTE)
00178 {
00179 angles::shortest_angular_distance_with_limits(
00180 current_position,
00181 command_position,
00182 joint_urdf_->limits->lower,
00183 joint_urdf_->limits->upper,
00184 error);
00185 }
00186 else if (joint_urdf_->type == urdf::Joint::CONTINUOUS)
00187 {
00188 error = angles::shortest_angular_distance(current_position, command_position);
00189 }
00190 else
00191 {
00192 error = command_position - current_position;
00193 }
00194
00195
00196 if (has_velocity_)
00197 {
00198
00199 vel_error = command_velocity - joint_.getVelocity();
00200
00201
00202
00203 commanded_velocity = pid_controller_.computeCommand(error, vel_error, period);
00204 }
00205 else
00206 {
00207
00208
00209 commanded_velocity = pid_controller_.computeCommand(error, period);
00210 }
00211
00212 joint_.setCommand(commanded_velocity);
00213
00214
00215 if (loop_count_ % 10 == 0)
00216 {
00217 if(controller_state_publisher_ && controller_state_publisher_->trylock())
00218 {
00219 controller_state_publisher_->msg_.header.stamp = time;
00220 controller_state_publisher_->msg_.set_point = command_position;
00221 controller_state_publisher_->msg_.process_value = current_position;
00222 controller_state_publisher_->msg_.process_value_dot = joint_.getVelocity();
00223 controller_state_publisher_->msg_.error = error;
00224 controller_state_publisher_->msg_.time_step = period.toSec();
00225 controller_state_publisher_->msg_.command = commanded_velocity;
00226
00227 double dummy;
00228 getGains(controller_state_publisher_->msg_.p,
00229 controller_state_publisher_->msg_.i,
00230 controller_state_publisher_->msg_.d,
00231 controller_state_publisher_->msg_.i_clamp,
00232 dummy);
00233 controller_state_publisher_->unlockAndPublish();
00234 }
00235 }
00236 loop_count_++;
00237 }
00238
00239 void JointPositionController::setCommandCB(const std_msgs::Float64ConstPtr& msg)
00240 {
00241 setCommand(msg->data);
00242 }
00243
00244
00245 void JointPositionController::enforceJointLimits(double &command)
00246 {
00247
00248 if (joint_urdf_->type == urdf::Joint::REVOLUTE || joint_urdf_->type == urdf::Joint::PRISMATIC)
00249 {
00250 if( command > joint_urdf_->limits->upper )
00251 {
00252 command = joint_urdf_->limits->upper;
00253 }
00254 else if( command < joint_urdf_->limits->lower )
00255 {
00256 command = joint_urdf_->limits->lower;
00257 }
00258 }
00259 }
00260
00261 }
00262
00263 PLUGINLIB_EXPORT_CLASS( velocity_controllers::JointPositionController, controller_interface::ControllerBase)