Skip to content

Commit 7907501

Browse files
authored
Python PlanningScene API: add set_current_state() (#3481)
1 parent 4ed1078 commit 7907501

File tree

1 file changed

+20
-0
lines changed

1 file changed

+20
-0
lines changed

moveit_py/src/moveit/moveit_core/planning_scene/planning_scene.cpp

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -247,6 +247,26 @@ void initPlanningScene(py::module& m)
247247
This method will remove all collision object from the scene except for attached collision objects.
248248
)")
249249

250+
.def("set_current_state",
251+
py::overload_cast<const moveit_msgs::msg::RobotState&>(&planning_scene::PlanningScene::setCurrentState),
252+
py::arg("robot_state"),
253+
R"(
254+
Set the current state using a moveit_msgs::msg::RobotState message.
255+
256+
Args:
257+
robot_state (moveit_msgs.msg.RobotState): The robot state message to set as current state.
258+
)")
259+
260+
.def("set_current_state",
261+
py::overload_cast<const moveit::core::RobotState&>(&planning_scene::PlanningScene::setCurrentState),
262+
py::arg("robot_state"),
263+
R"(
264+
Set the current state using a moveit::core::RobotState object.
265+
266+
Args:
267+
robot_state (moveit_py.core.RobotState): The robot state object to set as current state.
268+
)")
269+
250270
// checking state validity
251271
.def("is_state_valid",
252272
py::overload_cast<const moveit::core::RobotState&, const std::string&, bool>(

0 commit comments

Comments
 (0)