Skip to content

Commit

Permalink
Revert "unittest: Use the not deprecated GeometryObject constructor"
Browse files Browse the repository at this point in the history
This reverts commit 43eba1e.
  • Loading branch information
jorisv committed May 24, 2024
1 parent 43eba1e commit fa1b641
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
8 changes: 4 additions & 4 deletions unittest/factory/cost.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -229,16 +229,16 @@ boost::shared_ptr<crocoddyl::CostModelAbstract> CostModelFactory::create(
pinocchio::GeomIndex ig_frame =
geometry->addGeometryObject(pinocchio::GeometryObject(
"frame", frame_index,
state->get_pinocchio()->frames[frame_index].parent, frame_SE3,
CollisionGeometryPtr(new hpp::fcl::Capsule(0, alpha))));
state->get_pinocchio()->frames[frame_index].parent,
CollisionGeometryPtr(new hpp::fcl::Capsule(0, alpha)), frame_SE3));
pinocchio::GeomIndex ig_obs =
geometry->addGeometryObject(pinocchio::GeometryObject(
"obs", state->get_pinocchio()->getFrameId("universe"),
state->get_pinocchio()
->frames[state->get_pinocchio()->getFrameId("universe")]
.parent,
frame_SE3_obstacle,
CollisionGeometryPtr(new hpp::fcl::Capsule(0, beta))));
CollisionGeometryPtr(new hpp::fcl::Capsule(0, beta)),
frame_SE3_obstacle));
geometry->addCollisionPair(pinocchio::CollisionPair(ig_frame, ig_obs));

switch (cost_type) {
Expand Down
8 changes: 4 additions & 4 deletions unittest/factory/residual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,15 +91,15 @@ ResidualModelFactory::create(ResidualModelTypes::Type residual_type,
pinocchio::GeomIndex ig_frame =
geometry->addGeometryObject(pinocchio::GeometryObject(
"frame", frame_index,
state->get_pinocchio()->frames[frame_index].parent, frame_SE3,
CollisionGeometryPtr(new hpp::fcl::Sphere(0))));
state->get_pinocchio()->frames[frame_index].parent,
CollisionGeometryPtr(new hpp::fcl::Sphere(0)), frame_SE3));
pinocchio::GeomIndex ig_obs =
geometry->addGeometryObject(pinocchio::GeometryObject(
"obs", state->get_pinocchio()->getFrameId("universe"),
state->get_pinocchio()
->frames[state->get_pinocchio()->getFrameId("universe")]
.parent, frame_SE3_obstacle,
CollisionGeometryPtr(new hpp::fcl::Sphere(0))));
.parent,
CollisionGeometryPtr(new hpp::fcl::Sphere(0)), frame_SE3_obstacle));
geometry->addCollisionPair(pinocchio::CollisionPair(ig_frame, ig_obs));
#endif // PINOCCHIO_WITH_HPP_FCL
if (nu == std::numeric_limits<std::size_t>::max()) {
Expand Down

0 comments on commit fa1b641

Please sign in to comment.