File tree Expand file tree Collapse file tree 1 file changed +20
-0
lines changed
moveit_py/src/moveit/moveit_core/planning_scene Expand file tree Collapse file tree 1 file changed +20
-0
lines changed Original file line number Diff line number Diff 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 >(
You can’t perform that action at this time.
0 commit comments