Skip to content

Commit

Permalink
Fix PlanarJointModel::satisfiesPositionBounds (moveit#1353)
Browse files Browse the repository at this point in the history
Co-authored-by: Vatan Aksoy Tezer <vatan@picknik.ai>
  • Loading branch information
2 people authored and peterdavidfagan committed Jul 14, 2022
1 parent dc26e58 commit 442840a
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion moveit_core/robot_model/src/planar_joint_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -271,7 +271,7 @@ double PlanarJointModel::distance(const double* values1, const double* values2)
bool PlanarJointModel::satisfiesPositionBounds(const double* values, const Bounds& bounds, double margin) const
{
for (unsigned int i = 0; i < 3; ++i)
if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
if (values[i] < bounds[i].min_position_ - margin || values[i] > bounds[i].max_position_ + margin)
return false;
return true;
}
Expand Down

0 comments on commit 442840a

Please sign in to comment.