Skip to content

Commit

Permalink
chore: sync files (autowarefoundation#168)
Browse files Browse the repository at this point in the history
* chore: sync files

Signed-off-by: GitHub <[email protected]>

* style(pre-commit): autofix

* Update unit_conversion.hpp

---------

Signed-off-by: GitHub <[email protected]>
Co-authored-by: kenji-miyake <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Kenji Miyake <[email protected]>
  • Loading branch information
4 people authored Apr 3, 2023
1 parent 9eb4bc4 commit 6dd5921
Show file tree
Hide file tree
Showing 7 changed files with 50 additions and 12 deletions.
1 change: 1 addition & 0 deletions .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ BasedOnStyle: Google

AccessModifierOffset: -2
AlignAfterOpenBracket: AlwaysBreak
AllowShortFunctionsOnASingleLine: InlineOnly
BraceWrapping:
AfterClass: true
AfterFunction: true
Expand Down
22 changes: 18 additions & 4 deletions autoware_utils/include/autoware_utils/math/unit_conversion.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,25 @@

namespace autoware_utils
{
constexpr double deg2rad(const double deg) { return deg * pi / 180.0; }
constexpr double rad2deg(const double rad) { return rad * 180.0 / pi; }
constexpr double deg2rad(const double deg)
{
return deg * pi / 180.0;
}

constexpr double rad2deg(const double rad)
{
return rad * 180.0 / pi;
}

constexpr double kmph2mps(const double kmph) { return kmph * 1000.0 / 3600.0; }
constexpr double mps2kmph(const double mps) { return mps * 3600.0 / 1000.0; }
constexpr double kmph2mps(const double kmph)
{
return kmph * 1000.0 / 3600.0;
}

constexpr double mps2kmph(const double mps)
{
return mps * 3600.0 / 1000.0;
}
} // namespace autoware_utils

#endif // AUTOWARE_UTILS__MATH__UNIT_CONVERSION_HPP_
10 changes: 8 additions & 2 deletions tmp/lanelet2_extension/lib/detection_area.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,10 @@ ConstPolygons3d DetectionArea::detectionAreas() const
{
return getConstPoly(parameters(), RoleName::Refers);
}
Polygons3d DetectionArea::detectionAreas() { return getPoly(parameters(), RoleName::Refers); }
Polygons3d DetectionArea::detectionAreas()
{
return getPoly(parameters(), RoleName::Refers);
}

void DetectionArea::addDetectionArea(const Polygon3d & primitive)
{
Expand All @@ -147,7 +150,10 @@ void DetectionArea::setStopLine(const LineString3d & stopLine)
parameters()[RoleName::RefLine] = {stopLine};
}

void DetectionArea::removeStopLine() { parameters()[RoleName::RefLine] = {}; }
void DetectionArea::removeStopLine()
{
parameters()[RoleName::RefLine] = {};
}

} // namespace lanelet::autoware

Expand Down
9 changes: 7 additions & 2 deletions tmp/lanelet2_extension/lib/mgrs_projector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,9 @@

namespace lanelet::projection
{
MGRSProjector::MGRSProjector(Origin origin) : Projector(origin) {}
MGRSProjector::MGRSProjector(Origin origin) : Projector(origin)
{
}

BasicPoint3d MGRSProjector::forward(const GPSPoint & gps) const
{
Expand Down Expand Up @@ -105,7 +107,10 @@ GPSPoint MGRSProjector::reverse(const BasicPoint3d & mgrs_point, const std::stri
return gps;
}

void MGRSProjector::setMGRSCode(const std::string & mgrs_code) { mgrs_code_ = mgrs_code; }
void MGRSProjector::setMGRSCode(const std::string & mgrs_code)
{
mgrs_code_ = mgrs_code;
}

void MGRSProjector::setMGRSCode(const GPSPoint & gps, const int precision)
{
Expand Down
10 changes: 8 additions & 2 deletions tmp/lanelet2_extension/lib/no_stopping_area.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,10 @@ ConstPolygons3d NoStoppingArea::noStoppingAreas() const
{
return getConstPoly(parameters(), RoleName::Refers);
}
Polygons3d NoStoppingArea::noStoppingAreas() { return getPoly(parameters(), RoleName::Refers); }
Polygons3d NoStoppingArea::noStoppingAreas()
{
return getPoly(parameters(), RoleName::Refers);
}

void NoStoppingArea::addNoStoppingArea(const Polygon3d & primitive)
{
Expand All @@ -147,7 +150,10 @@ void NoStoppingArea::setStopLine(const LineString3d & stopLine)
parameters()[RoleName::RefLine] = {stopLine};
}

void NoStoppingArea::removeStopLine() { parameters()[RoleName::RefLine] = {}; }
void NoStoppingArea::removeStopLine()
{
parameters()[RoleName::RefLine] = {};
}

} // namespace lanelet::autoware

Expand Down
5 changes: 4 additions & 1 deletion tmp/lanelet2_extension/lib/road_marking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,10 @@ void RoadMarking::setRoadMarking(const LineString3d & road_marking)
parameters()[RoleName::Refers] = {road_marking};
}

void RoadMarking::removeRoadMarking() { parameters()[RoleName::Refers] = {}; }
void RoadMarking::removeRoadMarking()
{
parameters()[RoleName::Refers] = {};
}

} // namespace lanelet::autoware

Expand Down
5 changes: 4 additions & 1 deletion tmp/lanelet2_extension/lib/speed_bump.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,10 @@ ConstPolygon3d SpeedBump::speedBump() const
return getConstPoly(parameters(), RoleName::Refers).front();
}

Polygon3d SpeedBump::speedBump() { return getPoly(parameters(), RoleName::Refers).front(); }
Polygon3d SpeedBump::speedBump()
{
return getPoly(parameters(), RoleName::Refers).front();
}

void SpeedBump::addSpeedBump(const Polygon3d & primitive)
{
Expand Down

0 comments on commit 6dd5921

Please sign in to comment.