Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update pre-commit #2465

Merged
merged 1 commit into from
Oct 22, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
2 changes: 2 additions & 0 deletions .codespell_words
Original file line number Diff line number Diff line change
Expand Up @@ -15,3 +15,5 @@ uint
whis
sinic
padd
brin
aas
6 changes: 3 additions & 3 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
repos:
# Standard hooks
- repo: https://github.com/pre-commit/pre-commit-hooks
rev: v4.4.0
rev: v4.5.0
hooks:
- id: check-added-large-files
- id: check-case-conflict
Expand All @@ -33,7 +33,7 @@ repos:
- id: trailing-whitespace

- repo: https://github.com/psf/black
rev: 23.3.0
rev: 23.10.0
hooks:
- id: black

Expand All @@ -47,7 +47,7 @@ repos:
files: \.(c|cc|cxx|cpp|frag|glsl|h|hpp|hxx|ih|ispc|ipp|java|js|m|proto|vert)$
args: ['-fallback-style=none', '-i']
- repo: https://github.com/codespell-project/codespell
rev: v2.2.4
rev: v2.2.6
hooks:
- id: codespell
args: ['--write-changes', '--ignore-words=.codespell_words', '--skip="*.eps"']
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ class BulletBVHManager
* @return true if successfully disabled, otherwise false. */
bool disableCollisionObject(const std::string& name);

/**@brief Set a single static collision object's tansform
/**@brief Set a single static collision object's transform
* @param name The name of the object
* @param pose The transformation in world */
void setCollisionObjectsTransform(const std::string& name, const Eigen::Isometry3d& pose);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ class BulletCastBVHManager : public BulletBVHManager
* This is to be used for multi threaded applications. A user should make a clone for each thread. */
BulletCastBVHManagerPtr clone() const;

/**@brief Set a single cast (moving) collision object's tansforms
/**@brief Set a single cast (moving) collision object's transforms
*
* This should only be used for moving objects.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1186,14 +1186,14 @@ class RobotState
/** \brief Set all joints in \e group to random values near the value in \e seed.
* \e distance is the maximum amount each joint value will vary from the
* corresponding value in \e seed. \distance represents meters for
* prismatic/postitional joints and radians for revolute/orientation joints.
* prismatic/positional joints and radians for revolute/orientation joints.
* Resulting values are clamped within default bounds. */
void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& seed, double distance);

/** \brief Set all joints in \e group to random values near the value in \e seed, using a specified random number generator.
* \e distance is the maximum amount each joint value will vary from the
* corresponding value in \e seed. \distance represents meters for
* prismatic/postitional joints and radians for revolute/orientation joints.
* prismatic/positional joints and radians for revolute/orientation joints.
* Resulting values are clamped within default bounds. */
void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& seed, double distance,
random_numbers::RandomNumberGenerator& rng);
Expand All @@ -1203,7 +1203,7 @@ class RobotState
* group.getActiveJointModels(). Each value in \e distances is the maximum
* amount the corresponding active joint in \e group will vary from the
* corresponding value in \e seed. \distance represents meters for
* prismatic/postitional joints and radians for revolute/orientation joints.
* prismatic/positional joints and radians for revolute/orientation joints.
* Resulting values are clamped within default bounds. */
void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& seed,
const std::vector<double>& distances);
Expand All @@ -1213,7 +1213,7 @@ class RobotState
* group.getActiveJointModels(). Each value in \e distances is the maximum
* amount the corresponding active joint in \e group will vary from the
* corresponding value in \e seed. \distance represents meters for
* prismatic/postitional joints and radians for revolute/orientation joints.
* prismatic/positional joints and radians for revolute/orientation joints.
* Resulting values are clamped within default bounds. */
void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& seed,
const std::vector<double>& distances, random_numbers::RandomNumberGenerator& rng);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -267,7 +267,7 @@ class IkSolution : public IkSolutionBase<T>
}
}

std::vector<IkSingleDOFSolutionBase<T> > _vbasesol; ///< solution and their offsets if joints are mimiced
std::vector<IkSingleDOFSolutionBase<T> > _vbasesol; ///< solution and their offsets if joints are mimicked
std::vector<int> _vfree;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -312,7 +312,7 @@ bool SrvKinematicsPlugin::searchPositionIK(const std::vector<geometry_msgs::msg:
if (error_code.val != error_code.SUCCESS)
{
// TODO (JafarAbdi) Print the entire message for ROS2?
// RCLCPP_DEBUG("srv", "An IK that satisifes the constraints and is collision free could not be found."
// RCLCPP_DEBUG("srv", "An IK that satisfies the constraints and is collision free could not be found."
// << "\nRequest was: \n"
// << ik_srv.request.ik_request << "\nResponse was: \n"
// << ik_srv.response.solution);
Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/ompl/ompl_interface/test/load_test_robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ namespace ompl_interface_testing
{
/** \brief Robot independent test class setup
*
* The desired robot tests can be impelmented in a derived class in a generic way.
* The desired robot tests can be implemented in a derived class in a generic way.
*
* It is implemented this way to avoid the ros specific test framework
* outside moveit_ros.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -217,7 +217,7 @@ bool VelocityProfileATrap::setProfileStartVelocity(double pos1, double pos2, dou

if (s * vel1 <= 0)
{
// TODO initial velocity is in opposite derection of start-end vector
// TODO initial velocity is in opposite direction of start-end vector
return false;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ void createPTPRequest(const std::string& planning_group, const moveit::core::Rob

/**
* @brief check if the goal given in joint space is reached
* Only the last point in the trajectory is veryfied.
* Only the last point in the trajectory is verified.
* @param trajectory: generated trajectory
* @param goal: goal in joint space
* @param joint_position_tolerance
Expand All @@ -182,7 +182,7 @@ bool isGoalReached(const trajectory_msgs::msg::JointTrajectory& trajectory,

/**
* @brief check if the goal given in cartesian space is reached
* Only the last point in the trajectory is veryfied.
* Only the last point in the trajectory is verified.
* @param robot_model
* @param trajectory
* @param req
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -263,7 +263,7 @@ class IkSolution : public IkSolutionBase<T>
}
}

std::vector<IkSingleDOFSolutionBase<T> > _vbasesol; ///< solution and their offsets if joints are mimiced
std::vector<IkSingleDOFSolutionBase<T> > _vbasesol; ///< solution and their offsets if joints are mimicked
std::vector<int> _vfree;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ inline double IKlog(double f) { return log(f); }
#define IKFAST_SOLUTION_THRESH ((IkReal)1e-6)
#endif

// there are checkpoints in ikfast that are evaluated to make sure they are 0. This threshold speicfies by how much they can deviate
// there are checkpoints in ikfast that are evaluated to make sure they are 0. This threshold specifies by how much they can deviate
#ifndef IKFAST_EVALCOND_THRESH
#define IKFAST_EVALCOND_THRESH ((IkReal)0.00001)
#endif
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ class TrajectoryOperatorInterface
virtual bool reset() = 0;

protected:
// Reference trajectory to be precessed
// Reference trajectory to be processed
robot_trajectory::RobotTrajectoryPtr reference_trajectory_;
std::string group_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,7 @@ class GLRenderer
unsigned getHeight() const;

/**
* \brief set the size of fram buffers
* \brief set the size of frame buffers
* \author Suat Gedikli (gedikli@willowgarage.com)
* \param[in] width width of frame buffer in pixels
* \param[in] height height of frame buffer in pixels
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -225,7 +225,7 @@ class MeshFilterBase
void addJob(const JobPtr& job) const;

/**
* \brief sets the size of the fram buffers
* \brief sets the size of the frame buffers
* \author Suat Gedikli (gedikli@willowgarage.com)
* \param[in] width width of frame buffers in pixels
* \param[in] height height of frame buffers in pixels
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ class PerceptionWidget : public SetupStepWidget
QGroupBox* point_cloud_group_;
QGroupBox* depth_map_group_;

// Point Cloud plugin feilds
// Point Cloud plugin fields
QLineEdit* point_cloud_topic_field_;
QLineEdit* max_range_field_;
QLineEdit* point_subsample_field_;
Expand All @@ -95,7 +95,7 @@ class PerceptionWidget : public SetupStepWidget
QLineEdit* max_update_rate_field_;
QLineEdit* filtered_cloud_topic_field_;

// Depth Map plugin feilds
// Depth Map plugin fields
QLineEdit* image_topic_field_;
QLineEdit* queue_size_field_;
QLineEdit* near_clipping_field_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ class SetupConfig
*
* @param[in] package_path the path to the root of the config package
* @param[in] last_gen_time The time (if any) when the config package was last generated
* @parma[out] files Where to put the new generated files
* @param[out] files Where to put the new generated files
*/
virtual void collectFiles(const std::filesystem::path& /*package_path*/, const GeneratedTime& /*last_gen_time*/,
std::vector<GeneratedFilePtr>& /*files*/)
Expand Down