Skip to content

Commit

Permalink
Merge branch 'main' into fix/cppcheck_variableScope_per-2
Browse files Browse the repository at this point in the history
  • Loading branch information
kobayu858 committed Aug 13, 2024
2 parents a652c10 + 7382d66 commit dd5668e
Show file tree
Hide file tree
Showing 57 changed files with 2,481 additions and 357 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ localization/autoware_pose_covariance_modifier/** melike@leodrive.ai
localization/autoware_stop_filter/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/autoware_twist2accel/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/ekf_localizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp
localization/geo_pose_projector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/autoware_geo_pose_projector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/gyro_odometer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/localization_error_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/localization_util/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

#include <exception>
#include <string>
#include <utility>
#include <vector>

#define EIGEN_MPL2_ONLY
Expand Down Expand Up @@ -583,6 +584,148 @@ std::optional<geometry_msgs::msg::Point> intersect(
*/
bool intersects_convex(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2);

// Alternatives for Boost.Geometry ----------------------------------------------------------------

// TODO(mitukou1109): remove namespace when migrating to alternatives
namespace alt
{
class Vector2d
{
public:
Vector2d() : x_(0.0), y_(0.0) {}

Vector2d(const double x, const double y) : x_(x), y_(y) {}

double cross(const Vector2d & other) const { return x_ * other.y() - y_ * other.x(); }

double dot(const Vector2d & other) const { return x_ * other.x() + y_ * other.y(); }

double norm2() const { return x_ * x_ + y_ * y_; }

double norm() const { return std::sqrt(norm2()); }

Vector2d vector_triple(const Vector2d & v1, const Vector2d & v2) const
{
const auto tmp = this->cross(v1);
return {-v2.y() * tmp, v2.x() * tmp};
}

const double & x() const { return x_; }

double & x() { return x_; }

const double & y() const { return y_; }

double & y() { return y_; }

private:
double x_;
double y_;
};

// We use Vector2d to represent points, but we do not name the class Point2d directly
// as it has some vector operation functions.
using Point2d = Vector2d;
using Points2d = std::vector<Point2d>;

class ConvexPolygon2d
{
public:
explicit ConvexPolygon2d(const Points2d & vertices)
{
if (vertices.size() < 3) {
throw std::invalid_argument("At least 3 points are required for vertices.");
}
vertices_ = vertices;
}

explicit ConvexPolygon2d(Points2d && vertices)
{
if (vertices.size() < 3) {
throw std::invalid_argument("At least 3 points are required for vertices.");
}
vertices_ = std::move(vertices);
}

const Points2d & vertices() const { return vertices_; }

Points2d & vertices() { return vertices_; }

private:
Points2d vertices_;
};

inline Vector2d operator+(const Vector2d & v1, const Vector2d & v2)
{
return {v1.x() + v2.x(), v1.y() + v2.y()};
}

inline Vector2d operator-(const Vector2d & v1, const Vector2d & v2)
{
return {v1.x() - v2.x(), v1.y() - v2.y()};
}

inline Vector2d operator-(const Vector2d & v)
{
return {-v.x(), -v.y()};
}

inline Vector2d operator*(const double & s, const Vector2d & v)
{
return {s * v.x(), s * v.y()};
}

Point2d from_geom(const geometry_msgs::msg::Point & point);

Point2d from_boost(const autoware::universe_utils::Point2d & point);

ConvexPolygon2d from_boost(const autoware::universe_utils::Polygon2d & polygon);

autoware::universe_utils::Point2d to_boost(const Point2d & point);

autoware::universe_utils::Polygon2d to_boost(const ConvexPolygon2d & polygon);
} // namespace alt

double area(const alt::ConvexPolygon2d & poly);

alt::ConvexPolygon2d convex_hull(const alt::Points2d & points);

void correct(alt::ConvexPolygon2d & poly);

bool covered_by(const alt::Point2d & point, const alt::ConvexPolygon2d & poly);

bool disjoint(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2);

double distance(
const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end);

double distance(const alt::Point2d & point, const alt::ConvexPolygon2d & poly);

bool equals(const alt::Point2d & point1, const alt::Point2d & point2);

bool equals(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2);

bool intersects(
const alt::Point2d & seg1_start, const alt::Point2d & seg1_end, const alt::Point2d & seg2_start,
const alt::Point2d & seg2_end);

bool intersects(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2);

bool is_above(
const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end);

bool is_clockwise(const alt::ConvexPolygon2d & poly);

bool touches(
const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end);

bool touches(const alt::Point2d & point, const alt::ConvexPolygon2d & poly);

bool within(const alt::Point2d & point, const alt::ConvexPolygon2d & poly);

bool within(
const alt::ConvexPolygon2d & poly_contained, const alt::ConvexPolygon2d & poly_containing);

} // namespace autoware::universe_utils

#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__GEOMETRY_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -67,9 +67,9 @@ class ProcessingTimeNode : public std::enable_shared_from_this<ProcessingTimeNod
/**
* @brief Get the parent node
*
* @return std::shared_ptr<ProcessingTimeNode> Shared pointer to the parent node
* @return std::weak_ptr<ProcessingTimeNode> Weak pointer to the parent node
*/
std::shared_ptr<ProcessingTimeNode> get_parent_node() const;
std::weak_ptr<ProcessingTimeNode> get_parent_node() const;

/**
* @brief Get the child nodes
Expand Down Expand Up @@ -101,10 +101,10 @@ class ProcessingTimeNode : public std::enable_shared_from_this<ProcessingTimeNod
std::string get_name() const;

private:
const std::string name_; //!< Name of the node
double processing_time_{0.0}; //!< Processing time of the node
std::string comment_; //!< Comment for the node
std::shared_ptr<ProcessingTimeNode> parent_node_{nullptr}; //!< Shared pointer to the parent node
const std::string name_; //!< Name of the node
double processing_time_{0.0}; //!< Processing time of the node
std::string comment_; //!< Comment for the node
std::weak_ptr<ProcessingTimeNode> parent_node_; //!< Weak pointer to the parent node
std::vector<std::shared_ptr<ProcessingTimeNode>>
child_nodes_; //!< Vector of shared pointers to the child nodes
};
Expand Down
Loading

0 comments on commit dd5668e

Please sign in to comment.