From 521f76ee3b23aed61004e760c2e3040c3feaefe5 Mon Sep 17 00:00:00 2001 From: Takumi Ito Date: Wed, 9 Oct 2024 07:52:11 -0400 Subject: [PATCH] run pre-commit Signed-off-by: Takumi Ito --- .../astar_search.py | 2 +- .../scripts/bind/astar_search_pybind.cpp | 12 +++++------- 2 files changed, 6 insertions(+), 8 deletions(-) diff --git a/planning/autoware_freespace_planning_algorithms/autoware_freespace_planning_algorithms/astar_search.py b/planning/autoware_freespace_planning_algorithms/autoware_freespace_planning_algorithms/astar_search.py index 50741971a7f80..8078f3bb1e92f 100644 --- a/planning/autoware_freespace_planning_algorithms/autoware_freespace_planning_algorithms/astar_search.py +++ b/planning/autoware_freespace_planning_algorithms/autoware_freespace_planning_algorithms/astar_search.py @@ -71,7 +71,7 @@ def getWaypoints(self): ) return waypoints - + def getDistanceToObstacle(self, pose: Pose): pose_byte = serialize_message(pose) return self.astar_search.getDistanceToObstacle(pose_byte) diff --git a/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp b/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp index a86dfccb1ba5d..36a254e3a006f 100644 --- a/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp +++ b/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp @@ -119,11 +119,10 @@ namespace py = pybind11; // cppcheck-suppress syntaxError PYBIND11_MODULE(autoware_freespace_planning_algorithms_pybind, p) { - auto pyPlannerWaypointsVector = - py::class_(p, "PlannerWaypointsVector") - .def(py::init<>()) - .def_readwrite("waypoints", &PlannerWaypointsVector::waypoints) - .def_readwrite("length", &PlannerWaypointsVector::length); + auto pyPlannerWaypointsVector = py::class_(p, "PlannerWaypointsVector") + .def(py::init<>()) + .def_readwrite("waypoints", &PlannerWaypointsVector::waypoints) + .def_readwrite("length", &PlannerWaypointsVector::length); auto pyAstarParam = py::class_(p, "AstarParam") .def(py::init<>()) @@ -150,8 +149,7 @@ PYBIND11_MODULE(autoware_freespace_planning_algorithms_pybind, p) "goal_lat_distance_weight", &freespace_planning_algorithms::AstarParam::goal_lat_distance_weight); auto pyPlannerCommonParam = - py::class_( - p, "PlannerCommonParam") + py::class_(p, "PlannerCommonParam") .def(py::init<>()) .def_readwrite("time_limit", &freespace_planning_algorithms::PlannerCommonParam::time_limit) .def_readwrite("theta_size", &freespace_planning_algorithms::PlannerCommonParam::theta_size)