Skip to content

Commit a9e6aba

Browse files
authored
Merge pull request #51 from PlanSys2/use_geometry_pose
Use geometry pose
2 parents ae66b67 + 8a7c3e1 commit a9e6aba

File tree

10 files changed

+74
-90
lines changed

10 files changed

+74
-90
lines changed

plansys2_bt_example/CMakeLists.txt

Lines changed: 19 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -17,24 +17,22 @@ find_package(plansys2_pddl_parser REQUIRED)
1717
find_package(ament_index_cpp REQUIRED)
1818
find_package(plansys2_bt_actions REQUIRED)
1919

20-
if(NOT CMAKE_CXX_STANDARD)
21-
set(CMAKE_CXX_STANDARD 17)
22-
endif()
20+
2321

2422
set(dependencies
25-
rclcpp
26-
rclcpp_action
27-
geometry_msgs
28-
tf2_geometry_msgs
29-
nav2_msgs
30-
plansys2_msgs
31-
plansys2_domain_expert
32-
plansys2_executor
33-
plansys2_planner
34-
plansys2_problem_expert
35-
plansys2_pddl_parser
36-
ament_index_cpp
37-
plansys2_bt_actions
23+
rclcpp::rclcpp
24+
rclcpp_action::rclcpp_action
25+
plansys2_domain_expert::plansys2_domain_expert
26+
plansys2_executor::plansys2_executor
27+
plansys2_planner::plansys2_planner
28+
plansys2_problem_expert::plansys2_problem_expert
29+
plansys2_pddl_parser::plansys2_pddl_parser
30+
ament_index_cpp::ament_index_cpp
31+
plansys2_bt_actions::plansys2_bt_actions
32+
${geometry_msgs_TARGETS}
33+
${tf2_geometry_msgs_TARGETS}
34+
${nav2_msgs_TARGETS}
35+
${plansys2_msgs_TARGETS}
3836
)
3937

4038
include_directories(include)
@@ -55,18 +53,18 @@ add_library(plansys2_approach_object_bt_node SHARED src/behavior_tree_nodes/Appr
5553
list(APPEND plugin_libs plansys2_approach_object_bt_node)
5654

5755
foreach(bt_plugin ${plugin_libs})
58-
ament_target_dependencies(${bt_plugin} ${dependencies})
56+
target_link_libraries(${bt_plugin} PUBLIC ${dependencies})
5957
target_compile_definitions(${bt_plugin} PRIVATE BT_PLUGIN_EXPORT)
6058
endforeach()
6159

6260
add_executable(assemble_action_node src/assemble_action_node.cpp)
63-
ament_target_dependencies(assemble_action_node ${dependencies})
61+
target_link_libraries(assemble_action_node PUBLIC ${dependencies})
6462

6563
add_executable(assemble_controller_node src/assemble_controller_node.cpp)
66-
ament_target_dependencies(assemble_controller_node ${dependencies})
64+
target_link_libraries(assemble_controller_node PUBLIC ${dependencies})
6765

6866
add_executable(nav2_sim_node src/nav2_sim_node.cpp)
69-
ament_target_dependencies(nav2_sim_node ${dependencies})
67+
target_link_libraries(nav2_sim_node PUBLIC ${dependencies})
7068

7169
install(DIRECTORY launch pddl behavior_trees_xml config DESTINATION share/${PROJECT_NAME})
7270

@@ -77,7 +75,7 @@ install(TARGETS
7775
${plugin_libs}
7876
ARCHIVE DESTINATION lib
7977
LIBRARY DESTINATION lib
80-
RUNTIME DESTINATION lib/${PROJECT_NAME}
78+
RUNTIME DESTINATION bin
8179
)
8280

8381
if(BUILD_TESTING)
@@ -87,6 +85,4 @@ if(BUILD_TESTING)
8785
find_package(ament_cmake_gtest REQUIRED)
8886
endif()
8987

90-
ament_export_dependencies(${dependencies})
91-
9288
ament_package()

plansys2_bt_example/include/plansys2_bt_example/behavior_tree_nodes/Move.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
#include <string>
1919
#include <map>
2020

21-
#include "geometry_msgs/msg/pose2_d.hpp"
21+
#include "geometry_msgs/msg/pose.hpp"
2222
#include "nav2_msgs/action/navigate_to_pose.hpp"
2323

2424
#include "plansys2_bt_actions/BTActionNode.hpp"
@@ -49,7 +49,7 @@ class Move : public plansys2::BtActionNode<
4949

5050
private:
5151
int goal_reached_;
52-
std::map<std::string, geometry_msgs::msg::Pose2D> waypoints_;
52+
std::map<std::string, geometry_msgs::msg::Pose> waypoints_;
5353
};
5454

5555
} // namespace plansys2_bt_tests

plansys2_bt_example/src/assemble_controller_node.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
// limitations under the License.
1414

1515
#include <memory>
16+
#include <tuple>
1617

1718
#include "plansys2_pddl_parser/Utils.hpp"
1819

plansys2_bt_example/src/behavior_tree_nodes/Move.cpp

Lines changed: 7 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919

2020
#include "plansys2_bt_example/behavior_tree_nodes/Move.hpp"
2121

22-
#include "geometry_msgs/msg/pose2_d.hpp"
22+
#include "geometry_msgs/msg/pose.hpp"
2323
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
2424

2525
#include "behaviortree_cpp/behavior_tree.h"
@@ -60,10 +60,10 @@ Move::Move(
6060

6161
std::vector<double> coords;
6262
if (node->get_parameter_or("waypoint_coords." + wp, coords, {})) {
63-
geometry_msgs::msg::Pose2D pose;
64-
pose.x = coords[0];
65-
pose.y = coords[1];
66-
pose.theta = coords[2];
63+
geometry_msgs::msg::Pose pose;
64+
pose.position.x = coords[0];
65+
pose.position.y = coords[1];
66+
pose.orientation = tf2::toMsg(tf2::Quaternion({0.0, 0.0, 1.0}, coords[2]));
6767

6868
waypoints_[wp] = pose;
6969
} else {
@@ -85,7 +85,7 @@ Move::on_tick()
8585
std::string goal;
8686
getInput<std::string>("goal", goal);
8787

88-
geometry_msgs::msg::Pose2D pose2nav;
88+
geometry_msgs::msg::Pose pose2nav;
8989
if (waypoints_.find(goal) != waypoints_.end()) {
9090
pose2nav = waypoints_[goal];
9191
} else {
@@ -96,10 +96,7 @@ Move::on_tick()
9696

9797
goal_pos.header.frame_id = "map";
9898
goal_pos.header.stamp = node->now();
99-
goal_pos.pose.position.x = pose2nav.x;
100-
goal_pos.pose.position.y = pose2nav.y;
101-
goal_pos.pose.position.z = 0;
102-
goal_pos.pose.orientation = tf2::toMsg(tf2::Quaternion({0.0, 0.0, 1.0}, pose2nav.theta));
99+
goal_pos.pose = pose2nav;
103100

104101
goal_.pose = goal_pos;
105102
}

plansys2_cascade_example/CMakeLists.txt

Lines changed: 9 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -8,26 +8,26 @@ find_package(rclcpp_action REQUIRED)
88
find_package(plansys2_msgs REQUIRED)
99
find_package(plansys2_executor REQUIRED)
1010

11-
set(CMAKE_CXX_STANDARD 17)
11+
1212

1313
set(dependencies
14-
rclcpp
15-
rclcpp_action
16-
plansys2_msgs
17-
plansys2_executor
14+
rclcpp::rclcpp
15+
rclcpp_action::rclcpp_action
16+
plansys2_executor::plansys2_executor
17+
${plansys2_msgs_TARGETS}
1818
)
1919

2020
add_executable(move_action_node src/move_action_node.cpp)
21-
ament_target_dependencies(move_action_node ${dependencies})
21+
target_link_libraries(move_action_node PUBLIC ${dependencies})
2222

2323
add_executable(charge_action_node src/charge_action_node.cpp)
24-
ament_target_dependencies(charge_action_node ${dependencies})
24+
target_link_libraries(charge_action_node PUBLIC ${dependencies})
2525

2626
add_executable(ask_charge_action_node src/ask_charge_action_node.cpp)
27-
ament_target_dependencies(ask_charge_action_node ${dependencies})
27+
target_link_libraries(ask_charge_action_node PUBLIC ${dependencies})
2828

2929
add_executable(check_obstacles_node src/check_obstacles_node.cpp)
30-
ament_target_dependencies(check_obstacles_node ${dependencies})
30+
target_link_libraries(check_obstacles_node PUBLIC ${dependencies})
3131

3232
install(DIRECTORY launch pddl DESTINATION share/${PROJECT_NAME})
3333

@@ -48,6 +48,4 @@ if(BUILD_TESTING)
4848
find_package(ament_cmake_gtest REQUIRED)
4949
endif()
5050

51-
ament_export_dependencies(${dependencies})
52-
5351
ament_package()

plansys2_multidomain_example/CMakeLists.txt

Lines changed: 10 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -8,29 +8,29 @@ find_package(rclcpp_action REQUIRED)
88
find_package(plansys2_msgs REQUIRED)
99
find_package(plansys2_executor REQUIRED)
1010

11-
set(CMAKE_CXX_STANDARD 17)
11+
1212

1313
set(dependencies
14-
rclcpp
15-
rclcpp_action
16-
plansys2_msgs
17-
plansys2_executor
14+
rclcpp::rclcpp
15+
rclcpp_action::rclcpp_action
16+
plansys2_executor::plansys2_executor
17+
${plansys2_msgs_TARGETS}
1818
)
1919

2020
add_executable(move_action_node src/move_action_node.cpp)
21-
ament_target_dependencies(move_action_node ${dependencies})
21+
target_link_libraries(move_action_node PUBLIC ${dependencies})
2222

2323
add_executable(charge_action_node src/charge_action_node.cpp)
24-
ament_target_dependencies(charge_action_node ${dependencies})
24+
target_link_libraries(charge_action_node PUBLIC ${dependencies})
2525

2626
add_executable(ask_charge_action_node src/ask_charge_action_node.cpp)
27-
ament_target_dependencies(ask_charge_action_node ${dependencies})
27+
target_link_libraries(ask_charge_action_node PUBLIC ${dependencies})
2828

2929
add_executable(pick_object_action_node src/pick_object_action_node.cpp)
30-
ament_target_dependencies(pick_object_action_node ${dependencies})
30+
target_link_libraries(pick_object_action_node PUBLIC ${dependencies})
3131

3232
add_executable(place_object_action_node src/place_object_action_node.cpp)
33-
ament_target_dependencies(place_object_action_node ${dependencies})
33+
target_link_libraries(place_object_action_node PUBLIC ${dependencies})
3434

3535
install(DIRECTORY launch pddl_1 pddl_2 DESTINATION share/${PROJECT_NAME})
3636

@@ -52,6 +52,4 @@ if(BUILD_TESTING)
5252
find_package(ament_cmake_gtest REQUIRED)
5353
endif()
5454

55-
ament_export_dependencies(${dependencies})
56-
5755
ament_package()

plansys2_patrol_navigation_example/CMakeLists.txt

Lines changed: 12 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -14,28 +14,27 @@ find_package(plansys2_planner REQUIRED)
1414
find_package(plansys2_problem_expert REQUIRED)
1515
find_package(plansys2_pddl_parser REQUIRED)
1616

17-
set(CMAKE_CXX_STANDARD 17)
1817

1918
set(dependencies
20-
rclcpp
21-
rclcpp_action
22-
plansys2_msgs
23-
nav2_msgs
24-
plansys2_domain_expert
25-
plansys2_executor
26-
plansys2_planner
27-
plansys2_problem_expert
28-
plansys2_pddl_parser
19+
rclcpp::rclcpp
20+
rclcpp_action::rclcpp_action
21+
plansys2_domain_expert::plansys2_domain_expert
22+
plansys2_executor::plansys2_executor
23+
plansys2_planner::plansys2_planner
24+
plansys2_problem_expert::plansys2_problem_expert
25+
plansys2_pddl_parser::plansys2_pddl_parser
26+
${plansys2_msgs_TARGETS}
27+
${nav2_msgs_TARGETS}
2928
)
3029

3130
add_executable(move_action_node src/move_action_node.cpp)
32-
ament_target_dependencies(move_action_node ${dependencies})
31+
target_link_libraries(move_action_node PUBLIC ${dependencies})
3332

3433
add_executable(patrol_action_node src/patrol_action_node.cpp)
35-
ament_target_dependencies(patrol_action_node ${dependencies})
34+
target_link_libraries(patrol_action_node PUBLIC ${dependencies})
3635

3736
add_executable(patrolling_controller_node src/patrolling_controller_node.cpp)
38-
ament_target_dependencies(patrolling_controller_node ${dependencies})
37+
target_link_libraries(patrolling_controller_node PUBLIC ${dependencies})
3938

4039
install(DIRECTORY launch pddl params DESTINATION share/${PROJECT_NAME})
4140

@@ -55,6 +54,4 @@ if(BUILD_TESTING)
5554
find_package(ament_cmake_gtest REQUIRED)
5655
endif()
5756

58-
ament_export_dependencies(${dependencies})
59-
6057
ament_package()

plansys2_patrol_navigation_example/src/patrolling_controller_node.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
// limitations under the License.
1414

1515
#include <memory>
16+
#include <tuple>
1617

1718
#include "plansys2_pddl_parser/Utils.hpp"
1819

plansys2_simple_example/CMakeLists.txt

Lines changed: 7 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -7,22 +7,22 @@ find_package(rclcpp REQUIRED)
77
find_package(plansys2_msgs REQUIRED)
88
find_package(plansys2_executor REQUIRED)
99

10-
set(CMAKE_CXX_STANDARD 17)
10+
1111

1212
set(dependencies
13-
rclcpp
14-
plansys2_msgs
15-
plansys2_executor
13+
rclcpp::rclcpp
14+
plansys2_executor::plansys2_executor
15+
${plansys2_msgs_TARGETS}
1616
)
1717

1818
add_executable(move_action_node src/move_action_node.cpp)
19-
ament_target_dependencies(move_action_node ${dependencies})
19+
target_link_libraries(move_action_node PUBLIC ${dependencies})
2020

2121
add_executable(charge_action_node src/charge_action_node.cpp)
22-
ament_target_dependencies(charge_action_node ${dependencies})
22+
target_link_libraries(charge_action_node PUBLIC ${dependencies})
2323

2424
add_executable(ask_charge_action_node src/ask_charge_action_node.cpp)
25-
ament_target_dependencies(ask_charge_action_node ${dependencies})
25+
target_link_libraries(ask_charge_action_node PUBLIC ${dependencies})
2626

2727
install(DIRECTORY launch pddl DESTINATION share/${PROJECT_NAME})
2828

@@ -42,6 +42,4 @@ if(BUILD_TESTING)
4242
find_package(ament_cmake_gtest REQUIRED)
4343
endif()
4444

45-
ament_export_dependencies(${dependencies})
46-
4745
ament_package()

plansys2_simple_example_py/CMakeLists.txt

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -11,19 +11,19 @@ find_package(Python3 REQUIRED COMPONENTS Interpreter Development)
1111

1212
ament_python_install_package(${PROJECT_NAME})
1313

14-
set(CMAKE_CXX_STANDARD 17)
14+
1515

1616
set(dependencies
17-
rclcpp
18-
plansys2_msgs
19-
plansys2_executor
17+
rclcpp::rclcpp
18+
plansys2_executor::plansys2_executor
19+
${plansys2_msgs_TARGETS}
2020
)
2121

2222
add_executable(move_action_node src/move_action_node.cpp)
23-
ament_target_dependencies(move_action_node ${dependencies})
23+
target_link_libraries(move_action_node PUBLIC ${dependencies})
2424

2525
add_executable(ask_charge_action_node src/ask_charge_action_node.cpp)
26-
ament_target_dependencies(ask_charge_action_node ${dependencies})
26+
target_link_libraries(ask_charge_action_node PUBLIC ${dependencies})
2727

2828
install(DIRECTORY launch pddl DESTINATION share/${PROJECT_NAME})
2929

@@ -47,6 +47,4 @@ if(BUILD_TESTING)
4747
find_package(ament_cmake_gtest REQUIRED)
4848
endif()
4949

50-
ament_export_dependencies(${dependencies})
51-
5250
ament_package()

0 commit comments

Comments
 (0)