Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(tier4_autoware_utils): apply clang-tidy #1660

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@

namespace tier4_autoware_utils
{
namespace bg = boost::geometry;
h-ohta marked this conversation as resolved.
Show resolved Hide resolved

bool isClockwise(const Polygon2d & polygon);
Polygon2d inverseClockwise(const Polygon2d & polygon);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -421,7 +421,7 @@ inline geometry_msgs::msg::Transform pose2transform(const geometry_msgs::msg::Po
}

inline geometry_msgs::msg::TransformStamped pose2transform(
const geometry_msgs::msg::PoseStamped & pose, const std::string child_frame_id)
const geometry_msgs::msg::PoseStamped & pose, const std::string & child_frame_id)
{
geometry_msgs::msg::TransformStamped transform;
transform.header = pose.header;
Expand Down Expand Up @@ -453,7 +453,7 @@ inline Point2d transformPoint(
}

inline Eigen::Vector3d transformPoint(
const Eigen::Vector3d point, const geometry_msgs::msg::Pose pose)
const Eigen::Vector3d & point, const geometry_msgs::msg::Pose & pose)
{
geometry_msgs::msg::Transform transform;
transform.translation.x = pose.position.x;
Expand All @@ -466,7 +466,7 @@ inline Eigen::Vector3d transformPoint(
}

inline geometry_msgs::msg::Point transformPoint(
const geometry_msgs::msg::Point point, const geometry_msgs::msg::Pose pose)
const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Pose & pose)
{
const Eigen::Vector3d vec = Eigen::Vector3d(point.x, point.y, point.z);
auto transformed_vec = transformPoint(vec, pose);
Expand Down Expand Up @@ -554,21 +554,21 @@ inline geometry_msgs::msg::Pose inverseTransformPose(

// Transform point in world coordinates to local coordinates
inline Eigen::Vector3d inverseTransformPoint(
const Eigen::Vector3d point, const geometry_msgs::msg::Pose pose)
const Eigen::Vector3d & point, const geometry_msgs::msg::Pose & pose)
{
const Eigen::Quaterniond q(
pose.orientation.w, pose.orientation.x, pose.orientation.y, pose.orientation.z);
const Eigen::Matrix3d R = q.normalized().toRotationMatrix();

const Eigen::Vector3d local_origin(pose.position.x, pose.position.y, pose.position.z);
const Eigen::Vector3d local_point = R.transpose() * point - R.transpose() * local_origin;
Eigen::Vector3d local_point = R.transpose() * point - R.transpose() * local_origin;

return local_point;
}

// Transform point in world coordinates to local coordinates
inline geometry_msgs::msg::Point inverseTransformPoint(
const geometry_msgs::msg::Point point, const geometry_msgs::msg::Pose pose)
const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Pose & pose)
{
const Eigen::Vector3d local_vec =
inverseTransformPoint(Eigen::Vector3d(point.x, point.y, point.z), pose);
Expand Down Expand Up @@ -599,11 +599,7 @@ bool isDrivingForward(const Pose1 & src_pose, const Pose2 & dst_pose)
// check the first point direction
const double src_yaw = tf2::getYaw(getPose(src_pose).orientation);
const double pose_direction_yaw = calcAzimuthAngle(getPoint(src_pose), getPoint(dst_pose));
if (std::fabs(normalizeRadian(src_yaw - pose_direction_yaw)) < pi / 2.0) {
return true;
}

return false;
return std::fabs(normalizeRadian(src_yaw - pose_direction_yaw)) < pi / 2.0;
}

/**
Expand Down Expand Up @@ -700,7 +696,8 @@ geometry_msgs::msg::Pose calcInterpolatedPose(
}
} else {
// Get orientation by spherical linear interpolation
tf2::Transform src_tf, dst_tf;
tf2::Transform src_tf;
tf2::Transform dst_tf;
tf2::fromMsg(getPose(src_pose), src_tf);
tf2::fromMsg(getPose(dst_pose), dst_tf);
const auto & quaternion = tf2::slerp(src_tf.getRotation(), dst_tf.getRotation(), clamped_ratio);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@ namespace tier4_autoware_utils
{
struct PoseDeviation
{
double lateral;
double longitudinal;
double yaw;
double lateral{0.0};
double longitudinal{0.0};
double yaw{0.0};
};

inline double calcLateralDeviation(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point &
bg::append(polygon.outer(), point);
}

void appendPointToPolygon(Polygon2d & polygon, const Point2d point)
void appendPointToPolygon(Polygon2d & polygon, const Point2d & point)
{
bg::append(polygon.outer(), point);
}
Expand Down Expand Up @@ -160,7 +160,7 @@ Polygon2d toPolygon2d(
}

// NOTE: push back the first point in order to close polygon
if (polygon.outer().size() > 0) {
if (!polygon.outer().empty()) {
appendPointToPolygon(polygon, polygon.outer().front());
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,6 @@

#include <gtest/gtest.h>

namespace bg = boost::geometry;

using tier4_autoware_utils::Polygon2d;

namespace
Expand Down