From 0a4f1ba82d2081c1e25cb9c08f6fe1a18a1d455a Mon Sep 17 00:00:00 2001 From: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Date: Wed, 25 Oct 2023 02:52:50 -0400 Subject: [PATCH] Finally fix errors building new RobotTrajectory Python bindings docs (#2481) * Add missing parenthesis in Python bindings docstring * Fix more docstrings --- .../moveit_core/robot_trajectory/robot_trajectory.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.cpp b/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.cpp index bf2844896c3..183938e3ae8 100644 --- a/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.cpp +++ b/moveit_py/src/moveit/moveit_core/robot_trajectory/robot_trajectory.cpp @@ -140,6 +140,7 @@ void init_robot_trajectory(py::module& m) py::arg("path_tolerance") = 0.1, py::arg("resample_dt") = 0.1, py::arg("min_angle_change") = 0.001, R"( Adds time parameterization to the trajectory using the Time-Optimal Trajectory Generation (TOTG) algorithm. + Args: velocity_scaling_factor (float): The velocity scaling factor. acceleration_scaling_factor (float): The acceleration scaling factor. @@ -154,11 +155,12 @@ void init_robot_trajectory(py::module& m) py::arg("overshoot_threshold") = 0.01, R"( Applies Ruckig smoothing to the trajectory. + Args: velocity_scaling_factor (float): The velocity scaling factor. acceleration_scaling_factor (float): The acceleration scaling factor. mitigate_overshoot (bool): Whether to mitigate overshoot during smoothing (default: false). - overshoot_threshold (float): The maximum allowed overshoot during smoothing (default: 0.01 + overshoot_threshold (float): The maximum allowed overshoot during smoothing (default: 0.01). Returns: bool: True if the trajectory was successfully retimed, false otherwise. )") @@ -166,6 +168,7 @@ void init_robot_trajectory(py::module& m) py::arg("joint_filter") = std::vector(), R"( Get the trajectory as a moveit_msgs.msg.RobotTrajectory message. + Args: joint_filter (list[string]): List of joints to consider in creating the message. If empty, uses all joints. Returns: @@ -175,8 +178,9 @@ void init_robot_trajectory(py::module& m) py::arg("robot_state"), py::arg("msg"), R"( Set the trajectory from a moveit_msgs.msg.RobotTrajectory message. + Args: - robot_state (py:class:`moveit_py.core.RobotState`): The reference robot starting state. + robot_state (:py:class:`moveit_py.core.RobotState`): The reference robot starting state. msg (moveit_msgs.msg.RobotTrajectory): A ROS robot trajectory message. )"); // TODO (peterdavidfagan): support other methods such as appending trajectories