Skip to content

Commit

Permalink
More fixes to Python bindings docstrings (backport #2474) (#2478)
Browse files Browse the repository at this point in the history
(cherry picked from commit af339e8)

Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>
  • Loading branch information
mergify[bot] and sea-bass committed Oct 24, 2023
1 parent 64bc4ea commit de51465
Showing 1 changed file with 5 additions and 2 deletions.
Expand Up @@ -146,7 +146,6 @@ void init_robot_trajectory(py::module& m)
path_tolerance (float): The path tolerance to use for time parameterization (default: 0.1).
resample_dt (float): The time step to use for time parameterization (default: 0.1).
min_angle_change (float): The minimum angle change to use for time parameterization (default: 0.001).
)
Returns:
bool: True if the trajectory was successfully retimed, false otherwise.
)")
Expand All @@ -160,21 +159,25 @@ void init_robot_trajectory(py::module& m)
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
)
Returns:
bool: True if the trajectory was successfully retimed, false otherwise.
)")
.def("get_robot_trajectory_msg", &moveit_py::bind_robot_trajectory::get_robot_trajectory_msg,
py::arg("joint_filter") = std::vector<std::string>(),
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:
moveit_msgs.msg.RobotTrajectory: A ROS robot trajectory message.
)")
.def("set_robot_trajectory_msg", &moveit_py::bind_robot_trajectory::set_robot_trajectory_msg,
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.
msg (moveit_msgs.msg.RobotTrajectory): A ROS robot trajectory message.
)");
// TODO (peterdavidfagan): support other methods such as appending trajectories
}
Expand Down

0 comments on commit de51465

Please sign in to comment.