Skip to content

Commit d4a42bc

Browse files
committed
We actually do want to halt joint indices, not variable indices
1 parent 646f48b commit d4a42bc

File tree

3 files changed

+28
-23
lines changed

3 files changed

+28
-23
lines changed

moveit_ros/moveit_servo/include/moveit_servo/utils/common.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -166,16 +166,16 @@ double jointLimitVelocityScalingFactor(const Eigen::VectorXd& velocities,
166166
const moveit::core::JointBoundsVector& joint_bounds, double scaling_override);
167167

168168
/**
169-
* \brief Finds the joint variables that are exceeding allowable position limits.
169+
* \brief Finds the joint indices that are exceeding allowable position limits in at least one variable.
170170
* @param positions The joint positions.
171171
* @param velocities The current commanded velocities.
172172
* @param joint_bounds The allowable limits for the robot joints.
173173
* @param margins Additional buffer on the actual joint limits.
174-
* @return The joint variables that are violating the specified position limits.
174+
* @return The joint indices that violate the specified position limits.
175175
*/
176-
std::vector<size_t> jointVariablesToHalt(const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities,
177-
const moveit::core::JointBoundsVector& joint_bounds,
178-
const std::vector<double>& margins);
176+
std::vector<size_t> jointsToHalt(const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities,
177+
const moveit::core::JointBoundsVector& joint_bounds,
178+
const std::vector<double>& margins);
179179

180180
/**
181181
* \brief Helper function for converting Eigen::Isometry3d to geometry_msgs/TransformStamped.

moveit_ros/moveit_servo/src/servo.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -334,14 +334,14 @@ void Servo::setCommandType(const CommandType& command_type)
334334
expected_command_type_ = command_type;
335335
}
336336

337-
KinematicState Servo::haltJoints(const std::vector<size_t>& joint_variables_to_halt,
338-
const KinematicState& current_state, const KinematicState& target_state) const
337+
KinematicState Servo::haltJoints(const std::vector<size_t>& joint_indices_to_halt, const KinematicState& current_state,
338+
const KinematicState& target_state) const
339339
{
340340
KinematicState bounded_state(target_state.joint_names.size());
341341
bounded_state.joint_names = target_state.joint_names;
342342

343343
std::stringstream halting_joint_names;
344-
for (const auto idx : joint_variables_to_halt)
344+
for (const auto idx : joint_indices_to_halt)
345345
{
346346
halting_joint_names << bounded_state.joint_names[idx] + " ";
347347
}
@@ -361,7 +361,7 @@ KinematicState Servo::haltJoints(const std::vector<size_t>& joint_variables_to_h
361361
// Halt only the joints that are out of bounds
362362
bounded_state.positions = target_state.positions;
363363
bounded_state.velocities = target_state.velocities;
364-
for (const auto idx : joint_variables_to_halt)
364+
for (const auto idx : joint_indices_to_halt)
365365
{
366366
bounded_state.positions[idx] = current_state.positions[idx];
367367
bounded_state.velocities[idx] = 0.0;
@@ -534,14 +534,14 @@ KinematicState Servo::getNextJointState(const moveit::core::RobotStatePtr& robot
534534
target_state.velocities = (target_state.positions - current_state.positions) / servo_params_.publish_period;
535535

536536
// Check if any joints are going past joint position limits.
537-
const std::vector<size_t> joint_variables_to_halt =
538-
jointVariablesToHalt(target_state.positions, target_state.velocities, joint_bounds, joint_limit_margins_);
537+
const std::vector<size_t> joint_indices_to_halt =
538+
jointsToHalt(target_state.positions, target_state.velocities, joint_bounds, joint_limit_margins_);
539539

540540
// Apply halting if any joints need to be halted.
541-
if (!joint_variables_to_halt.empty())
541+
if (!joint_indices_to_halt.empty())
542542
{
543543
servo_status_ = StatusCode::JOINT_BOUND;
544-
target_state = haltJoints(joint_variables_to_halt, current_state, target_state);
544+
target_state = haltJoints(joint_indices_to_halt, current_state, target_state);
545545
}
546546
}
547547

moveit_ros/moveit_servo/src/utils/common.cpp

Lines changed: 15 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -408,33 +408,38 @@ double jointLimitVelocityScalingFactor(const Eigen::VectorXd& velocities,
408408
return min_scaling_factor;
409409
}
410410

411-
std::vector<size_t> jointVariablesToHalt(const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities,
412-
const moveit::core::JointBoundsVector& joint_bounds,
413-
const std::vector<double>& margins)
411+
std::vector<size_t> jointsToHalt(const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities,
412+
const moveit::core::JointBoundsVector& joint_bounds,
413+
const std::vector<double>& margins)
414414
{
415-
std::vector<size_t> variable_idxs_to_halt;
415+
std::vector<size_t> joint_indices_to_halt;
416416

417417
// Now get the scaling factor from joint velocity limits.
418-
size_t idx = 0;
418+
size_t joint_idx = 0;
419+
size_t variable_idx = 0;
419420
for (const auto& joint_bound : joint_bounds)
420421
{
421422
for (const auto& variable_bound : *joint_bound)
422423
{
423424
if (variable_bound.position_bounded_)
424425
{
425426
const bool approaching_negative_bound =
426-
velocities[idx] < 0 && positions[idx] < (variable_bound.min_position_ + margins[idx]);
427+
velocities[variable_idx] < 0 &&
428+
positions[variable_idx] < (variable_bound.min_position_ + margins[variable_idx]);
427429
const bool approaching_positive_bound =
428-
velocities[idx] > 0 && positions[idx] > (variable_bound.max_position_ - margins[idx]);
430+
velocities[variable_idx] > 0 &&
431+
positions[variable_idx] > (variable_bound.max_position_ - margins[variable_idx]);
429432
if (approaching_negative_bound || approaching_positive_bound)
430433
{
431-
variable_idxs_to_halt.push_back(idx);
434+
joint_indices_to_halt.push_back(joint_idx);
435+
break; // No need to add the same joint index more than once.
432436
}
433437
}
434-
++idx;
438+
++variable_idx;
435439
}
440+
++joint_idx;
436441
}
437-
return variable_idxs_to_halt;
442+
return joint_indices_to_halt;
438443
}
439444

440445
/** \brief Helper function for converting Eigen::Isometry3d to geometry_msgs/TransformStamped **/

0 commit comments

Comments
 (0)