Skip to content

Commit f1c1ab4

Browse files
authored
Merge branch 'main' into pr-port-planning-scene-fix
2 parents e8224d4 + 9b3d96a commit f1c1ab4

File tree

4 files changed

+16
-18
lines changed

4 files changed

+16
-18
lines changed

moveit_core/package.xml

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -41,13 +41,7 @@
4141
<depend>libfcl-dev</depend>
4242
<depend>moveit_common</depend>
4343
<depend>moveit_msgs</depend>
44-
<!--
45-
Temporarily disable octomap dependency because of
46-
version conflict. We use liboctomap-dev provided
47-
by libfcl-dev.
48-
See https://github.com/moveit/moveit2/issues/2862
49-
<depend>octomap</depend>
50-
-->
44+
<depend>liboctomap-dev</depend>
5145
<depend>octomap_msgs</depend>
5246
<depend>osqp_vendor</depend>
5347
<depend>pluginlib</depend>

moveit_py/src/moveit/moveit_ros/moveit_cpp/moveit_cpp.cpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -60,8 +60,9 @@ void initMoveitPy(py::module& m)
6060
The MoveItPy class is the main interface to the MoveIt Python API. It is a wrapper around the MoveIt C++ API.
6161
)")
6262

63-
.def(py::init([](const std::string& node_name, const std::vector<std::string>& launch_params_filepaths,
64-
const py::object& config_dict, bool provide_planning_service) {
63+
.def(py::init([](const std::string& node_name, const std::string& name_space,
64+
const std::vector<std::string>& launch_params_filepaths, const py::object& config_dict,
65+
bool provide_planning_service) {
6566
// This section is used to load the appropriate node parameters before spinning a moveit_cpp instance
6667
// Priority is given to parameters supplied directly via a config_dict, followed by launch parameters
6768
// and finally no supplied parameters.
@@ -106,7 +107,7 @@ void initMoveitPy(py::module& m)
106107
.arguments(launch_arguments);
107108

108109
RCLCPP_INFO(getLogger(), "Initialize node and executor");
109-
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(node_name, "", node_options);
110+
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(node_name, name_space, node_options);
110111
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> executor =
111112
std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
112113

@@ -133,7 +134,7 @@ void initMoveitPy(py::module& m)
133134

134135
return moveit_cpp_ptr;
135136
}),
136-
py::arg("node_name") = "moveit_py",
137+
py::arg("node_name") = "moveit_py", py::arg("name_space") = "",
137138
py::arg("launch_params_filepaths") =
138139
utils.attr("get_launch_params_filepaths")().cast<std::vector<std::string>>(),
139140
py::arg("config_dict") = py::none(), py::arg("provide_planning_service") = true,

moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -175,6 +175,15 @@ void initPlanningSceneMonitor(py::module& m)
175175
attached_collision_object_msg (moveit_msgs.msg.AttachedCollisionObject): The attached collision object to apply to the planning scene.
176176
)")
177177

178+
.def("new_planning_scene_message", &planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneMessage,
179+
py::arg("scene"),
180+
R"(
181+
Called to update the planning scene with a new message.
182+
183+
Args:
184+
scene (moveit_msgs.msg.PlanningScene): The new planning scene message.
185+
)")
186+
178187
.def("read_only", &moveit_py::bind_planning_scene_monitor::readOnly,
179188
R"(
180189
Returns a read-only context manager for the planning scene.

moveit_ros/occupancy_map_monitor/package.xml

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -26,13 +26,7 @@
2626
<depend>rclcpp</depend>
2727
<depend>moveit_core</depend>
2828
<depend>moveit_msgs</depend>
29-
<!--
30-
Temporarily disable octomap dependency because of
31-
version conflict. We use liboctomap-dev provided
32-
by moveit_core->libfcl-dev.
33-
See https://github.com/moveit/moveit2/issues/2862
34-
<depend>octomap</depend>
35-
-->
29+
<depend>liboctomap-dev</depend>
3630
<depend version_gte="1.11.2">pluginlib</depend>
3731
<depend>tf2_ros</depend>
3832
<depend>geometric_shapes</depend>

0 commit comments

Comments
 (0)