diff --git a/source/armarx/navigation/components/navigator/Component.cpp b/source/armarx/navigation/components/navigator/Component.cpp index 34d27ae7372d410a97cdab175d67543b0f4ad074..3509d2f331fd0408d1cbe57d47c6a6aaa094f778 100644 --- a/source/armarx/navigation/components/navigator/Component.cpp +++ b/source/armarx/navigation/components/navigator/Component.cpp @@ -258,7 +258,7 @@ namespace armarx::navigation::components::navigator fac::NavigationStackFactory::create(stackConfig, sceneProvider->scene()); // set visualization of LocalPlanner - stack.localPlanner->setVisualization(&getArvizClient()); + stack.localPlanner->setVisualization(getArvizClient()); memoryIntrospectors.emplace_back( std::make_unique<server::MemoryIntrospector>(resultsWriterPlugin->get(), callerId)); diff --git a/source/armarx/navigation/local_planning/LocalPlanner.cpp b/source/armarx/navigation/local_planning/LocalPlanner.cpp index 4b7ea7ed74a41cec3e7f01c31c320d77ade4a813..ab0fbd229acf07ea26833e9a77481fe923f6237e 100644 --- a/source/armarx/navigation/local_planning/LocalPlanner.cpp +++ b/source/armarx/navigation/local_planning/LocalPlanner.cpp @@ -7,8 +7,8 @@ namespace armarx::navigation::local_planning } void - LocalPlanner::setVisualization(viz::Client* vis) + LocalPlanner::setVisualization(viz::Client& vis) { - arviz = vis; + arviz.emplace(vis); } } // namespace armarx::navigation::local_planning diff --git a/source/armarx/navigation/local_planning/LocalPlanner.h b/source/armarx/navigation/local_planning/LocalPlanner.h index f2f6641b622a78101a4fd5892d0170ce764c4661..031318818e623d942d7acd3469d5bf771722890f 100644 --- a/source/armarx/navigation/local_planning/LocalPlanner.h +++ b/source/armarx/navigation/local_planning/LocalPlanner.h @@ -58,10 +58,10 @@ namespace armarx::navigation::local_planning virtual std::optional<LocalPlannerResult> plan(const core::GlobalTrajectory& goal) = 0; - void setVisualization(viz::Client* vis); + void setVisualization(viz::Client& vis); protected: - viz::Client* arviz; + std::optional<viz::ScopedClient> arviz; private: const core::Scene& context; diff --git a/source/armarx/navigation/local_planning/TebObstacleManager.cpp b/source/armarx/navigation/local_planning/TebObstacleManager.cpp index 5e46a90175f9455ac1a8ab42176f862605d991d4..c7288854b8e39b3f7a606d691120901a041eb4c7 100644 --- a/source/armarx/navigation/local_planning/TebObstacleManager.cpp +++ b/source/armarx/navigation/local_planning/TebObstacleManager.cpp @@ -29,7 +29,7 @@ namespace armarx::navigation::local_planning auto obst = boost::make_shared<teb_local_planner::PolygonObstacle>(); const Eigen::Vector2d min = conv::toRos(bbox.getMin()); - const Eigen::Vector2d max = conv::toRos(bbox.getMin()); + const Eigen::Vector2d max = conv::toRos(bbox.getMax()); obst->pushBackVertex(min); obst->pushBackVertex(min.x(), max.y()); diff --git a/source/armarx/navigation/local_planning/TimedElasticBands.cpp b/source/armarx/navigation/local_planning/TimedElasticBands.cpp index 2633583dafd120cf02f10839d8cc26b131b90aae..daedf66c4b09cc71ad9dbe9fb3513a8dfd629a2b 100644 --- a/source/armarx/navigation/local_planning/TimedElasticBands.cpp +++ b/source/armarx/navigation/local_planning/TimedElasticBands.cpp @@ -130,9 +130,9 @@ namespace armarx::navigation::local_planning core::LocalTrajectory best = conv::fromRos(hcp_->findBestTeb()->teb()); // visualize path alternatives - if (arviz != nullptr) + if (arviz) { - auto layer = arviz->layer("local_planner_path_alternatives"); + auto layer = arviz.value().layer("local_planner_path_alternatives"); int i = 0; int bestTebIdx = hcp_->bestTebIdx(); @@ -152,7 +152,8 @@ namespace armarx::navigation::local_planning .color(simox::Color::gray())); i++; } - arviz->commit(layer); + + arviz.value().commit(layer); } return {{.trajectory = best}}; @@ -165,9 +166,9 @@ namespace armarx::navigation::local_planning viz::Layer* visPtr = nullptr; viz::Layer visLayer; - if (arviz != nullptr) + if (arviz) { - visLayer = arviz->layer("local_planner_obstacles"); + visLayer = arviz.value().layer("local_planner_obstacles"); visPtr = &visLayer; } @@ -189,9 +190,9 @@ namespace armarx::navigation::local_planning } } - if (arviz != nullptr) + if (arviz) { - arviz->commit(visLayer); + arviz.value().commit(visLayer); } ARMARX_INFO << "TEB: added " << obstManager.size() << " obstacles";