diff --git a/src/tutorial_1.cc b/src/tutorial_1.cc index 103eea8cb32d82b2262f03ae329a04ab961e0114..3609adc2d8417a3920286e8104407ed1aca03b72 100644 --- a/src/tutorial_1.cc +++ b/src/tutorial_1.cc @@ -42,7 +42,8 @@ int main() { // Add obstacle DevicePtr_t obstacle = Device::create("kitchen"); - hpp::pinocchio::urdf::loadModel(obstacle, 0, "", "anchor", + hpp::pinocchio::urdf::loadModel( + obstacle, 0, "", "anchor", "package://hpp_tutorial/urdf/kitchen_area.urdf", ""); obstacle->controlComputation(JOINT_POSITION); ps->addObstacle(obstacle, true, true); diff --git a/src/tutorial_2.cc b/src/tutorial_2.cc index 22f0148fcfecaa4c313bffd76d0a0150fd61b26c..51b038bd88e7d72f117371f703b70eea51c7d8a8 100644 --- a/src/tutorial_2.cc +++ b/src/tutorial_2.cc @@ -110,7 +110,7 @@ class Planner : public core::PathPlanner { } } } - for(auto de : delayedEdges){ + for (auto de : delayedEdges) { r->addEdge(std::get<0>(de), std::get<1>(de), std::get<2>(de)); r->addEdge(std::get<1>(de), std::get<0>(de), std::get<2>(de)->reverse()); }