Skip to content

Commit 62727b0

Browse files
pre-commit-ci[bot]liuXinGangChina
authored andcommitted
style(pre-commit): autofix
1 parent 7ae2d81 commit 62727b0

File tree

7 files changed

+21
-20
lines changed

7 files changed

+21
-20
lines changed

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/README.md

+3-2
Original file line numberDiff line numberDiff line change
@@ -16,12 +16,14 @@ Package motion velocity planner is responsible for generating velocity profiles
1616

1717
1. **Polygon Utilities (`polygon_utils.hpp`)**
1818
This component provides functions for handling geometric polygons related to motion planning. It includes:
19+
1920
- Collision detection between trajectories and obstacles.
2021
- Creation of polygons representing the vehicle's trajectory at different time steps.
2122
- Geometric calculations using Boost Geometry.
2223

2324
2. **General Utilities (`utils.hpp`)**
2425
This component provides various utility functions, including:
26+
2527
- Conversion between point representations (e.g., `pcl::PointXYZ` to `geometry_msgs::msg::Point`).
2628
- Distance calculations between trajectory points and obstacles.
2729
- Functions for concatenating vectors and processing trajectories.
@@ -32,7 +34,6 @@ Package motion velocity planner is responsible for generating velocity profiles
3234
- `SlowdownInterval`: Represents a segment where the vehicle should slow down, with specified start and end points and velocity.
3335
- `VelocityPlanningResult`: Contains a collection of stop points, slowdown intervals, and optional velocity limits and clear commands.
3436

35-
3637
## Usage
3738

3839
### Including the Package
@@ -55,4 +56,4 @@ const auto decimated_traj_points = autoware::motion_velocity_planner::utils::dec
5556
p.decimate_trajectory_step_length, 0.0);
5657
```
5758

58-
this example is from autoware_universe/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp
59+
this example is from autoware_universe/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/obstacle_cruise_module.cpp

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/collision_checker.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__COLLISION_CHECKER_HPP_
16-
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__COLLISION_CHECKER_HPP_
15+
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_
16+
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_
1717

1818
#include <autoware_utils/geometry/boost_geometry.hpp>
1919

@@ -66,4 +66,4 @@ class CollisionChecker
6666
};
6767
} // namespace autoware::motion_velocity_planner
6868

69-
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__COLLISION_CHECKER_HPP_
69+
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__COLLISION_CHECKER_HPP_

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLANNER_DATA_HPP_
16-
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLANNER_DATA_HPP_
15+
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_
16+
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_
1717

1818
#include <autoware/motion_utils/distance/distance.hpp>
1919
#include <autoware/motion_utils/trajectory/trajectory.hpp>
@@ -191,4 +191,4 @@ struct PlannerData
191191
};
192192
} // namespace autoware::motion_velocity_planner
193193

194-
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLANNER_DATA_HPP_
194+
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/plugin_module_interface.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLUGIN_MODULE_INTERFACE_HPP_
16-
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLUGIN_MODULE_INTERFACE_HPP_
15+
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLUGIN_MODULE_INTERFACE_HPP_
16+
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLUGIN_MODULE_INTERFACE_HPP_
1717

1818
#include "planner_data.hpp"
1919
#include "velocity_planning_result.hpp"
@@ -62,4 +62,4 @@ class PluginModuleInterface
6262

6363
} // namespace autoware::motion_velocity_planner
6464

65-
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__PLUGIN_MODULE_INTERFACE_HPP_
65+
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLUGIN_MODULE_INTERFACE_HPP_

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/polygon_utils.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__POLYGON_UTILS_HPP_
16-
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__POLYGON_UTILS_HPP_
15+
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__POLYGON_UTILS_HPP_
16+
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__POLYGON_UTILS_HPP_
1717

1818
#include "autoware_utils/geometry/boost_geometry.hpp"
1919
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
@@ -79,4 +79,4 @@ std::vector<Polygon2d> create_one_step_polygons(
7979
} // namespace polygon_utils
8080
} // namespace autoware::motion_velocity_planner
8181

82-
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__POLYGON_UTILS_HPP_
82+
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__POLYGON_UTILS_HPP_

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/utils.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__UTILS_HPP_
16-
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__UTILS_HPP_
15+
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__UTILS_HPP_
16+
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__UTILS_HPP_
1717

1818
#include "autoware_utils/geometry/geometry.hpp"
1919
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
@@ -145,4 +145,4 @@ double calc_possible_min_dist_from_obj_to_traj_poly(
145145
const std::vector<TrajectoryPoint> & traj_points, const VehicleInfo & vehicle_info);
146146
} // namespace autoware::motion_velocity_planner::utils
147147

148-
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__UTILS_HPP_
148+
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__UTILS_HPP_

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/velocity_planning_result.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__VELOCITY_PLANNING_RESULT_HPP_
16-
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__VELOCITY_PLANNING_RESULT_HPP_
15+
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__VELOCITY_PLANNING_RESULT_HPP_
16+
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__VELOCITY_PLANNING_RESULT_HPP_
1717

1818
#include <autoware/motion_utils/marker/virtual_wall_marker_creator.hpp>
1919

@@ -50,4 +50,4 @@ struct VelocityPlanningResult
5050
};
5151
} // namespace autoware::motion_velocity_planner
5252

53-
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON_UNIVERSE__VELOCITY_PLANNING_RESULT_HPP_
53+
#endif // AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__VELOCITY_PLANNING_RESULT_HPP_

0 commit comments

Comments
 (0)