53 JointPositionController::~JointPositionController()
55 sub_command_.shutdown();
61 std::string joint_name;
62 if (!n.
getParam(
"joint", joint_name))
73 controller_state_publisher_.reset(
77 sub_command_ = n.
subscribe<std_msgs::Float64>(
"command", 1, &JointPositionController::setCommandCB,
this);
84 if (!
urdf.initParamWithNodeHandle(
"robot_description", n))
89 joint_urdf_ =
urdf.getJoint(joint_name);
92 ROS_ERROR(
"Could not find joint '%s' in urdf", joint_name.c_str());
99 void JointPositionController::setGains(
const double &p,
const double &i,
const double &d,
const double &i_max,
const double &i_min,
const bool &antiwindup)
101 pid_controller_.setGains(p,i,d,i_max,i_min,antiwindup);
104 void JointPositionController::getGains(
double &p,
double &i,
double &d,
double &i_max,
double &i_min)
107 pid_controller_.getGains(p,i,d,i_max,i_min,dummy);
110 void JointPositionController::getGains(
double &p,
double &i,
double &d,
double &i_max,
double &i_min,
bool &antiwindup)
112 pid_controller_.getGains(p,i,d,i_max,i_min,antiwindup);
115 void JointPositionController::printDebug()
117 pid_controller_.printValues();
120 std::string JointPositionController::getJointName()
122 return joint_.getName();
125 double JointPositionController::getPosition()
127 return joint_.getPosition();
131 void JointPositionController::setCommand(
double pos_command)
133 command_struct_.position_ = pos_command;
134 command_struct_.has_velocity_ =
false;
139 command_.writeFromNonRT(command_struct_);
143 void JointPositionController::setCommand(
double pos_command,
double vel_command)
145 command_struct_.position_ = pos_command;
146 command_struct_.velocity_ = vel_command;
147 command_struct_.has_velocity_ =
true;
149 command_.writeFromNonRT(command_struct_);
152 void JointPositionController::starting(
const ros::Time& time)
154 double pos_command = joint_.getPosition();
157 enforceJointLimits(pos_command);
159 command_struct_.position_ = pos_command;
160 command_struct_.has_velocity_ =
false;
162 command_.initRT(command_struct_);
164 pid_controller_.reset();
169 command_struct_ = *(command_.readFromRT());
170 double command_position = command_struct_.position_;
171 double command_velocity = command_struct_.velocity_;
172 bool has_velocity_ = command_struct_.has_velocity_;
174 double error, vel_error;
175 double commanded_velocity;
177 double current_position = joint_.getPosition();
180 enforceJointLimits(command_position);
183 if (joint_urdf_->type == urdf::Joint::REVOLUTE)
188 joint_urdf_->limits->lower,
189 joint_urdf_->limits->upper,
192 else if (joint_urdf_->type == urdf::Joint::CONTINUOUS)
198 error = command_position - current_position;
205 vel_error = command_velocity - joint_.getVelocity();
209 commanded_velocity = pid_controller_.computeCommand(error, vel_error, period);
215 commanded_velocity = pid_controller_.computeCommand(error, period);
218 joint_.setCommand(commanded_velocity);
221 if (loop_count_ % 10 == 0)
223 if(controller_state_publisher_ && controller_state_publisher_->trylock())
225 controller_state_publisher_->msg_.header.stamp = time;
226 controller_state_publisher_->msg_.set_point = command_position;
227 controller_state_publisher_->msg_.process_value = current_position;
228 controller_state_publisher_->msg_.process_value_dot = joint_.getVelocity();
229 controller_state_publisher_->msg_.error = error;
230 controller_state_publisher_->msg_.time_step = period.
toSec();
231 controller_state_publisher_->msg_.command = commanded_velocity;
235 getGains(controller_state_publisher_->msg_.p,
236 controller_state_publisher_->msg_.i,
237 controller_state_publisher_->msg_.d,
238 controller_state_publisher_->msg_.i_clamp,
241 controller_state_publisher_->msg_.antiwindup =
static_cast<char>(antiwindup);
242 controller_state_publisher_->unlockAndPublish();
248 void JointPositionController::setCommandCB(
const std_msgs::Float64ConstPtr& msg)
250 setCommand(msg->data);
254 void JointPositionController::enforceJointLimits(
double &command)
257 if (joint_urdf_->type == urdf::Joint::REVOLUTE || joint_urdf_->type == urdf::Joint::PRISMATIC)
259 if( command > joint_urdf_->limits->upper )
261 command = joint_urdf_->limits->upper;
263 else if( command < joint_urdf_->limits->lower )
265 command = joint_urdf_->limits->lower;