Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions moveit_core/robot_model/src/planar_joint_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -271,6 +271,7 @@ void PlanarJointModel::interpolate(const double* from, const double* to, const d
state[1] = to[1];
state[2] = drive_angle + final_turn * percent;
}
normalizeRotation(state);
}
}

Expand Down
20 changes: 20 additions & 0 deletions moveit_core/robot_model/test/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,6 +204,26 @@ TEST(PlanarJointTest, ComputeVariablePositionsNormalizeYaw)
}
}

TEST(PlanarJointTest, InterpolateNormalizesYaw)
{
// Create a simple planar joint model with some dummy parameters
moveit::core::PlanarJointModel pjm("joint", 0, 0);

// Test for normalization
const double from[3] = { 0.0, 0.0, -2.9 };
const double to[3] = { 0.0, 0.0, 3.0 };

// Check that yaw value is normalized between [-pi, pi]
for (auto model : { moveit::core::PlanarJointModel::HOLONOMIC, moveit::core::PlanarJointModel::DIFF_DRIVE })
{
pjm.setMotionModel(model);
double state[3];
pjm.interpolate(from, to, 1.0, state);
EXPECT_GE(state[2], -M_PI) << "model=" << model << " theta=" << state[2];
EXPECT_LE(state[2], M_PI) << "model=" << model << " theta=" << state[2];
}
}

int main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);
Expand Down
Loading