30 KDL::Twist v_out(v_in);
33 v_out = (*it)->enforceLimits(v_out);
41 KDL::JntArray q_dot_norm(q_dot_ik);
44 q_dot_norm = (*it)->enforceLimits(q_dot_norm, q);
152 KDL::JntArray q_dot_norm(q_dot_ik);
154 double max_factor = 1.0;
155 int joint_index = -1;
157 for (
unsigned int i = 0; i < q_dot_ik.rows(); i++)
162 ROS_ERROR_STREAM(
"Joint " << i <<
" violates its limits. Setting to Zero!");
163 KDL::SetToZero(q_dot_norm);
173 if (temp > max_factor)
187 if (temp > max_factor)
196 if (max_factor > 1.0)
198 ROS_ERROR_STREAM_THROTTLE(1,
"Position tolerance surpassed (by Joint " << joint_index <<
"): Scaling ALL VELOCITIES with factor = " << max_factor);
199 for (
unsigned int i = 0; i < q_dot_ik.rows(); i++)
201 q_dot_norm(i) = q_dot_ik(i) / max_factor;
216 KDL::JntArray q_dot_norm(q_dot_ik);
217 double max_factor = 1.0;
218 int joint_index = -1;
220 for (
unsigned int i = 0; i < q_dot_ik.rows(); i++)
229 if (max_factor > 1.0)
231 ROS_WARN_STREAM_THROTTLE(1,
"Velocity limit surpassed (by Joint " << joint_index <<
"): Scaling ALL VELOCITIES with factor = " << max_factor);
232 for (
unsigned int i = 0; i < q_dot_ik.rows(); i++)
234 q_dot_norm(i) = q_dot_ik(i) / max_factor;
249 KDL::JntArray q_dot_norm(q_dot_ik);
251 ROS_WARN(
"LimiterAllJointAccelerations not yet implemented");
264 KDL::Twist v_out(v_in);
266 double max_factor = 1.0;
274 if (max_factor > 1.0)
276 ROS_WARN_STREAM_THROTTLE(1,
"Cartesian velocity limit surpassed: Scaling ALL VELOCITIES with factor = " << max_factor);
277 v_out.rot.x(v_in.rot.x()/max_factor);
278 v_out.rot.y(v_in.rot.y()/max_factor);
279 v_out.rot.z(v_in.rot.z()/max_factor);
280 v_out.vel.x(v_in.vel.x()/max_factor);
281 v_out.vel.y(v_in.vel.y()/max_factor);
282 v_out.vel.z(v_in.vel.z()/max_factor);
297 KDL::JntArray q_dot_norm(q_dot_ik);
300 for (
unsigned int i = 0; i < q_dot_ik.rows(); i++)
305 ROS_ERROR_STREAM(
"Joint " << i <<
" violates its limits. Setting to Zero!");
312 if (q_dot_ik(i) > 0.0)
316 factor = (temp > factor) ? temp : factor;
322 if (q_dot_ik(i) < 0.0)
326 factor = (temp > factor) ? temp : factor;
329 q_dot_norm(i) = q_dot_norm(i) / factor;
343 KDL::JntArray q_dot_norm(q_dot_ik);
345 for (
unsigned int i = 0; i < q_dot_ik.rows(); i++)
351 q_dot_norm(i) = q_dot_ik(i) / factor;
366 KDL::JntArray q_dot_norm(q_dot_ik);
368 ROS_WARN(
"LimiterIndividualJointAccelerations not yet implemented");
381 KDL::Twist v_out(v_in);