diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 0965dba..67244e5 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -15,18 +15,18 @@ repos: - id: sort-simple-yaml - id: trailing-whitespace - # - repo: https://github.com/pocc/pre-commit-hooks - # rev: master - # hooks: - # - id: clang-format - # args: [--style=Google, -i] - # # - id: clang-tidy - # # args: [--fix-errors] - # - id: cppcheck - # - id: cpplint - # # - id: oclint - # # - id: uncrustify - # # - id: include-what-you-use + - repo: https://github.com/pocc/pre-commit-hooks + rev: master + hooks: + - id: cppcheck + # - id: cpplint + # - id: clang-format + # args: [--style=Google, -i] + # - id: clang-tidy + # args: [--fix-errors] + # - id: oclint + # - id: uncrustify + # - id: include-what-you-use - repo: https://github.com/astral-sh/ruff-pre-commit rev: "v0.1.6" diff --git a/src/me5413_world/src/path_publisher_node.cpp b/src/me5413_world/src/path_publisher_node.cpp index b355439..290ed7c 100644 --- a/src/me5413_world/src/path_publisher_node.cpp +++ b/src/me5413_world/src/path_publisher_node.cpp @@ -22,7 +22,7 @@ double LOCAL_PREV_WP_NUM; double LOCAL_NEXT_WP_NUM; bool PARAMS_UPDATED = false; -void dynamicParamCallback(me5413_world::path_publisherConfig& config, uint32_t level) +void dynamicParamCallback(const me5413_world::path_publisherConfig& config, uint32_t level) { // Common Params SPEED_TARGET = config.speed_target; @@ -201,8 +201,6 @@ void PathPublisherNode::publishLocalPath(const geometry_msgs::Pose &robot_pose, int PathPublisherNode::closestWaypoint(const geometry_msgs::Pose &robot_pose, const nav_msgs::Path &path, const int id_start = 0) { - const double yaw_robot = getYawFromOrientation(robot_pose.orientation); - double min_dist = DBL_MAX; int id_closest = id_start; for (int i = id_start; i < path.poses.size(); i++) diff --git a/src/me5413_world/src/path_tracker_node.cpp b/src/me5413_world/src/path_tracker_node.cpp index 9c20fdb..19ab019 100644 --- a/src/me5413_world/src/path_tracker_node.cpp +++ b/src/me5413_world/src/path_tracker_node.cpp @@ -19,7 +19,7 @@ double PID_Kp, PID_Ki, PID_Kd; double STANLEY_K; bool PARAMS_UPDATED; -void dynamicParamCallback(me5413_world::path_trackerConfig& config, uint32_t level) +void dynamicParamCallback(const me5413_world::path_trackerConfig& config, uint32_t level) { // Common Params SPEED_TARGET = config.speed_target;