diff --git a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h index 8d75d3da4f2..7854022874c 100644 --- a/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h +++ b/moveit_core/collision_detection_bullet/include/moveit/collision_detection_bullet/collision_env_bullet.h @@ -96,8 +96,8 @@ class CollisionEnvBullet : public CollisionEnv void updatedPaddingOrScaling(const std::vector& links) override; /** \brief All of the attached objects in the robot state are wrapped into bullet collision objects */ - void addAttachedOjects(const moveit::core::RobotState& state, - std::vector& cows) const; + void addAttachedObjects(const moveit::core::RobotState& state, + std::vector& cows) const; /** \brief Bundles the different checkSelfCollision functions into a single function */ void checkSelfCollisionHelper(const CollisionRequest& req, CollisionResult& res, diff --git a/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp b/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp index 36c7894d277..ad1d8cf7d3a 100644 --- a/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp +++ b/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp @@ -119,7 +119,7 @@ void CollisionEnvBullet::checkSelfCollisionHelper(const CollisionRequest& req, C std::lock_guard guard(collision_env_mutex_); std::vector cows; - addAttachedOjects(state, cows); + addAttachedObjects(state, cows); if (req.distance) { @@ -187,7 +187,7 @@ void CollisionEnvBullet::checkRobotCollisionHelper(const CollisionRequest& req, } std::vector attached_cows; - addAttachedOjects(state, attached_cows); + addAttachedObjects(state, attached_cows); updateTransformsFromState(state, manager_); for (const collision_detection_bullet::CollisionObjectWrapperPtr& cow : attached_cows) @@ -213,7 +213,7 @@ void CollisionEnvBullet::checkRobotCollisionHelperCCD(const CollisionRequest& re std::lock_guard guard(collision_env_mutex_); std::vector attached_cows; - addAttachedOjects(state1, attached_cows); + addAttachedObjects(state1, attached_cows); for (const collision_detection_bullet::CollisionObjectWrapperPtr& cow : attached_cows) { @@ -331,8 +331,8 @@ void CollisionEnvBullet::notifyObjectChange(const ObjectConstPtr& obj, World::Ac } } -void CollisionEnvBullet::addAttachedOjects(const moveit::core::RobotState& state, - std::vector& cows) const +void CollisionEnvBullet::addAttachedObjects(const moveit::core::RobotState& state, + std::vector& cows) const { std::vector attached_bodies; state.getAttachedBodies(attached_bodies); 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 33397b15255..fc6eb6f314e 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 @@ -139,7 +139,7 @@ void init_robot_trajectory(py::module& m) py::arg("velocity_scaling_factor"), py::arg("acceleration_scaling_factor"), py::kw_only(), 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. + 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,7 +154,7 @@ void init_robot_trajectory(py::module& m) py::arg("acceleration_scaling_factor"), py::kw_only(), py::arg("mitigate_overshoot") = false, py::arg("overshoot_threshold") = 0.01, R"( - Applies Ruckig smoothing to the trajectory. + Applies Ruckig smoothing to the trajectory. Args: velocity_scaling_factor (float): The velocity scaling factor. acceleration_scaling_factor (float): The acceleration scaling factor. @@ -168,8 +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. - - Returns: + Returns: moveit_msgs.msg.RobotTrajectory: A ROS robot trajectory message. )") .def("set_robot_trajectory_msg", &moveit_py::bind_robot_trajectory::set_robot_trajectory_msg,