Skip to content

Commit 8118309

Browse files
committed
Cleanup + address deprecation warnings
1 parent 2868297 commit 8118309

File tree

4 files changed

+3
-10
lines changed

4 files changed

+3
-10
lines changed

core/src/solvers/pipeline_planner.cpp

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -49,10 +49,6 @@
4949
#include <tf2_eigen/tf2_eigen.h>
5050
#endif
5151

52-
namespace {
53-
const std::pair<std::string, std::string> DEFAULT_REQUESTED_PIPELINE =
54-
std::pair<std::string, std::string>("ompl", "RRTConnect");
55-
}
5652
namespace moveit {
5753
namespace task_constructor {
5854
namespace solvers {

core/test/pick_pa10.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -47,8 +47,7 @@ TEST(PA10, pick) {
4747
t.setProperty("eef", std::string("la_tool_mount"));
4848
t.setProperty("gripper", std::string("left_hand"));
4949

50-
auto pipeline = std::make_shared<solvers::PipelinePlanner>(node);
51-
pipeline->setPlannerId("RRTConnectkConfigDefault");
50+
auto pipeline = std::make_shared<solvers::PipelinePlanner>(node, "ompl", "RRTConnectkConfigDefault");
5251
auto cartesian = std::make_shared<solvers::CartesianPath>();
5352

5453
Stage* initial_stage = nullptr;

core/test/pick_pr2.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -40,8 +40,7 @@ TEST(PR2, pick) {
4040

4141
auto node = rclcpp::Node::make_shared("pr2");
4242
// planner used for connect
43-
auto pipeline = std::make_shared<solvers::PipelinePlanner>(node);
44-
pipeline->setPlannerId("RRTConnectkConfigDefault");
43+
auto pipeline = std::make_shared<solvers::PipelinePlanner>(node, "ompl", "RRTConnectkConfigDefault");
4544
// connect to pick
4645
stages::Connect::GroupPlannerVector planners = { { "left_arm", pipeline }, { "left_gripper", pipeline } };
4746
auto connect = std::make_unique<stages::Connect>("connect", planners);

core/test/pick_ur5.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,7 @@ TEST(UR5, pick) {
4242

4343
auto node = rclcpp::Node::make_shared("ur5");
4444
// planner used for connect
45-
auto pipeline = std::make_shared<solvers::PipelinePlanner>(node);
46-
pipeline->setPlannerId("RRTConnectkConfigDefault");
45+
auto pipeline = std::make_shared<solvers::PipelinePlanner>(node, "ompl", "RRTConnectkConfigDefault");
4746
// connect to pick
4847
stages::Connect::GroupPlannerVector planners = { { "arm", pipeline }, { "gripper", pipeline } };
4948
auto connect = std::make_unique<stages::Connect>("connect", planners);

0 commit comments

Comments
 (0)