Skip to content

Commit

Permalink
Merge branch 'main' into node_logging
Browse files Browse the repository at this point in the history
  • Loading branch information
tylerjw authored Oct 25, 2023
2 parents b9efa98 + 0a4f1ba commit f033924
Showing 1 changed file with 6 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand All @@ -154,18 +155,20 @@ 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.
)")
.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:
Expand All @@ -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
Expand Down

0 comments on commit f033924

Please sign in to comment.