@@ -27,7 +27,7 @@ namespace math
2727namespace geometry
2828{
2929auto CatmullRomSpline::getPolygon (
30- const double width, const size_t num_points, const double z_offset)
30+ const double width, const std:: size_t num_points, const double z_offset)
3131 -> std::vector<geometry_msgs::msg::Point>
3232{
3333 if (num_points == 0 ) {
@@ -36,7 +36,7 @@ auto CatmullRomSpline::getPolygon(
3636 std::vector<geometry_msgs::msg::Point> points;
3737 std::vector<geometry_msgs::msg::Point> left_bounds = getLeftBounds (width, num_points, z_offset);
3838 std::vector<geometry_msgs::msg::Point> right_bounds = getRightBounds (width, num_points, z_offset);
39- for (size_t i = 0 ; i < left_bounds.size () - 1 ; i++) {
39+ for (std:: size_t i = 0 ; i < left_bounds.size () - 1 ; i++) {
4040 geometry_msgs::msg::Point pr_0 = right_bounds[i];
4141 geometry_msgs::msg::Point pl_0 = left_bounds[i];
4242 geometry_msgs::msg::Point pr_1 = right_bounds[i + 1 ];
@@ -52,12 +52,12 @@ auto CatmullRomSpline::getPolygon(
5252}
5353
5454auto CatmullRomSpline::getRightBounds (
55- const double width, const size_t num_points, const double z_offset) const
55+ const double width, const std:: size_t num_points, const double z_offset) const
5656 -> std::vector<geometry_msgs::msg::Point>
5757{
5858 std::vector<geometry_msgs::msg::Point> points;
5959 double step_size = getLength () / static_cast <double >(num_points);
60- for (size_t i = 0 ; i < num_points + 1 ; i++) {
60+ for (std:: size_t i = 0 ; i < num_points + 1 ; i++) {
6161 double s = step_size * static_cast <double >(i);
6262 points.emplace_back (
6363 [this ](const double local_width, const double local_s, const double local_z_offset) {
@@ -75,12 +75,12 @@ auto CatmullRomSpline::getRightBounds(
7575}
7676
7777auto CatmullRomSpline::getLeftBounds (
78- const double width, const size_t num_points, const double z_offset) const
78+ const double width, const std:: size_t num_points, const double z_offset) const
7979 -> std::vector<geometry_msgs::msg::Point>
8080{
8181 std::vector<geometry_msgs::msg::Point> points;
8282 double step_size = getLength () / static_cast <double >(num_points);
83- for (size_t i = 0 ; i < num_points + 1 ; i++) {
83+ for (std:: size_t i = 0 ; i < num_points + 1 ; i++) {
8484 double s = step_size * static_cast <double >(i);
8585 points.emplace_back (
8686 [this ](const double local_width, const double local_s, const double local_z_offset) {
@@ -142,8 +142,8 @@ CatmullRomSpline::CatmullRomSpline(const std::vector<geometry_msgs::msg::Point>
142142 // / @note In this case, spline is interpreted as curve.
143143 default :
144144 [this ](const auto & control_points) -> void {
145- size_t n = control_points.size () - 1 ;
146- for (size_t i = 0 ; i < n; i++) {
145+ std:: size_t n = control_points.size () - 1 ;
146+ for (std:: size_t i = 0 ; i < n; i++) {
147147 if (i == 0 ) {
148148 double ax = 0 ;
149149 double bx = control_points[0 ].x - 2 * control_points[1 ].x + control_points[2 ].x ;
@@ -244,7 +244,7 @@ CatmullRomSpline::CatmullRomSpline(const std::vector<geometry_msgs::msg::Point>
244244 }
245245}
246246
247- auto CatmullRomSpline::getCurveIndexAndS (const double s) const -> std::pair<size_t, double>
247+ auto CatmullRomSpline::getCurveIndexAndS (const double s) const -> std::pair<std:: size_t, double>
248248{
249249 if (s < 0 ) {
250250 return std::make_pair (0 , s);
@@ -254,7 +254,7 @@ auto CatmullRomSpline::getCurveIndexAndS(const double s) const -> std::pair<size
254254 curves_.size () - 1 , s - (total_length_ - curves_[curves_.size () - 1 ].getLength ()));
255255 }
256256 double current_s = 0 ;
257- for (size_t i = 0 ; i < curves_.size (); i++) {
257+ for (std:: size_t i = 0 ; i < curves_.size (); i++) {
258258 double prev_s = current_s;
259259 current_s = current_s + length_list_[i];
260260 if (prev_s <= s && s < current_s) {
@@ -264,11 +264,12 @@ auto CatmullRomSpline::getCurveIndexAndS(const double s) const -> std::pair<size
264264 THROW_SIMULATION_ERROR (" failed to calculate curve index" ); // LCOV_EXCL_LINE
265265}
266266
267- auto CatmullRomSpline::getSInSplineCurve (const size_t curve_index, const double s) const -> double
267+ auto CatmullRomSpline::getSInSplineCurve (const std::size_t curve_index, const double s) const
268+ -> double
268269{
269- size_t n = curves_.size ();
270+ std:: size_t n = curves_.size ();
270271 double ret = 0 ;
271- for (size_t i = 0 ; i < n; i++) {
272+ for (std:: size_t i = 0 ; i < n; i++) {
272273 if (i == curve_index) {
273274 return ret + s;
274275 } else {
@@ -295,7 +296,7 @@ auto CatmullRomSpline::getCollisionPointsIn2D(
295296 const auto local_search_backward) {
296297 std::set<double > s_value_candidates;
297298 auto current_curve_start_s = 0.0 ;
298- for (size_t i = 0 ; i < curves_.size (); ++i) {
299+ for (std::std:: size_t i = 0 ; i < curves_.size (); ++i) {
299300 if (
300301 s_range == std::nullopt ||
301302 (current_curve_start_s >= s_range->first && current_curve_start_s <= s_range->second )) {
@@ -383,17 +384,17 @@ auto CatmullRomSpline::getCollisionPointIn2D(
383384 const geometry_msgs::msg::Point & point0, const geometry_msgs::msg::Point & point1,
384385 const bool search_backward) const -> std::optional<double>
385386{
386- size_t n = curves_.size ();
387+ std:: size_t n = curves_.size ();
387388 if (search_backward) {
388- for (size_t i = 0 ; i < n; i++) {
389+ for (std:: size_t i = 0 ; i < n; i++) {
389390 auto s = curves_[n - 1 - i].getCollisionPointIn2D (point0, point1, search_backward, true );
390391 if (s) {
391392 return getSInSplineCurve (n - 1 - i, s.value ());
392393 }
393394 }
394395 return std::nullopt ;
395396 } else {
396- for (size_t i = 0 ; i < n; i++) {
397+ for (std:: size_t i = 0 ; i < n; i++) {
397398 auto s = curves_[i].getCollisionPointIn2D (point0, point1, search_backward, true );
398399 if (s) {
399400 return getSInSplineCurve (i, s.value ());
@@ -435,7 +436,7 @@ auto CatmullRomSpline::getSValue(
435436 return line_segments_[0 ].getSValue (pose, threshold_distance, true );
436437 default :
437438 double s = 0 ;
438- for (size_t i = 0 ; i < curves_.size (); i++) {
439+ for (std:: size_t i = 0 ; i < curves_.size (); i++) {
439440 auto s_value = curves_[i].getSValue (pose, threshold_distance, true );
440441 if (s_value) {
441442 s = s + s_value.value ();
@@ -692,7 +693,7 @@ auto CatmullRomSpline::checkConnection() const -> bool
692693 THROW_SIMULATION_ERROR ( // LCOV_EXCL_LINE
693694 " number of control points and curves does not match." ); // LCOV_EXCL_LINE
694695 }
695- for (size_t i = 0 ; i < curves_.size (); i++) {
696+ for (std:: size_t i = 0 ; i < curves_.size (); i++) {
696697 const auto control_point0 = control_points[i];
697698 const auto control_point1 = control_points[i + 1 ];
698699 const auto p0 = curves_[i].getPoint (0 , false );
0 commit comments