Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Jun 13, 2024
1 parent e567388 commit 4b7e0eb
Show file tree
Hide file tree
Showing 9 changed files with 35 additions and 38 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,10 @@ struct Color
}

explicit Color(const cv::Scalar & rgb, float a = 1.0f)
: r(static_cast<float>(rgb[2]) / 255.f), g(static_cast<float>(rgb[1]) / 255.f),
b(static_cast<float>(rgb[0]) / 255.f), a(a)
: r(static_cast<float>(rgb[2]) / 255.f),
g(static_cast<float>(rgb[1]) / 255.f),
b(static_cast<float>(rgb[0]) / 255.f),
a(a)
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,10 @@ void inline upsample_line_string(
const lanelet::ConstPoint3d & from, const lanelet::ConstPoint3d & to,
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
{
Eigen::Vector3f f(static_cast<float>(from.x()), static_cast<float>(from.y()),
static_cast<float>(from.z()));
Eigen::Vector3f t(static_cast<float>(to.x()), static_cast<float>(to.y()),
static_cast<float>(to.z()));
Eigen::Vector3f f(
static_cast<float>(from.x()), static_cast<float>(from.y()), static_cast<float>(from.z()));
Eigen::Vector3f t(
static_cast<float>(to.x()), static_cast<float>(to.y()), static_cast<float>(to.z()));
float length = (t - f).norm();
Eigen::Vector3f d = (t - f).normalized();
for (float l = 0; l < length; l += 0.5f) {
Expand All @@ -44,8 +44,7 @@ void inline upsample_line_string(
};

std::vector<int> inline merge_indices(
const std::vector<int> & indices1, const std::vector<int> & indices2
)
const std::vector<int> & indices1, const std::vector<int> & indices2)
{
std::unordered_set<int> set;
for (int i : indices1) set.insert(i);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class Ll2Decomposer : public rclcpp::Node
void on_map(const LaneletMapBin & msg);

static pcl::PointNormal to_point_normal(
const lanelet::ConstPoint3d & from, const lanelet::ConstPoint3d & to) ;
const lanelet::ConstPoint3d & from, const lanelet::ConstPoint3d & to);

static pcl::PointCloud<pcl::PointNormal> split_line_strings(
const lanelet::ConstLineStrings3d & line_strings);
Expand Down
15 changes: 5 additions & 10 deletions localization/yabloc/yabloc_common/src/color.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,16 +42,11 @@ Color hsv_to_rgb(float h_, float s_, float v_)
const float max = v_;
const float min = max * (1.0f - s_);

if (h < 60)
return {max, h / 60 * (max - min) + min, min};
if (h < 120)
return {(120 - h) / 60 * (max - min) + min, max, min};
if (h < 180)
return {min, max, (h - 120) / 60 * (max - min) + min};
if (h < 240)
return {min, (240 - h) / 60 * (max - min) + min, max};
if (h < 300)
return {(h - 240) / 60 * (max - min) + min, min, max};
if (h < 60) return {max, h / 60 * (max - min) + min, min};
if (h < 120) return {(120 - h) / 60 * (max - min) + min, max, min};
if (h < 180) return {min, max, (h - 120) / 60 * (max - min) + min};
if (h < 240) return {min, (240 - h) / 60 * (max - min) + min, max};
if (h < 300) return {(h - 240) / 60 * (max - min) + min, min, max};
return {max, min, (360 - h) / 60 * (max - min) + min};
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,7 @@ pcl::PointCloud<pcl::PointNormal> extract_near_line_segments(

// All line segments contained in a square with max_range on one side must be taken out,
// so pick up those that are closer than the **diagonals** of the square.
auto check_intersection = [max_range,
pose_vector](const pcl::PointNormal & pn) -> bool {
auto check_intersection = [max_range, pose_vector](const pcl::PointNormal & pn) -> bool {
const Eigen::Vector3f from = pn.getVector3fMap() - pose_vector;
const Eigen::Vector3f to = pn.getNormalVector3fMap() - pose_vector;

Expand All @@ -42,8 +41,9 @@ pcl::PointCloud<pcl::PointNormal> extract_near_line_segments(
};

pcl::PointCloud<pcl::PointNormal> dst;
std::copy_if(line_segments.begin(), line_segments.end(), std::back_inserter(dst),
[check_intersection](const auto& pn) { return check_intersection(pn); });
std::copy_if(
line_segments.begin(), line_segments.end(), std::back_inserter(dst),
[check_intersection](const auto & pn) { return check_intersection(pn); });
return dst;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,14 +21,15 @@
#include <yabloc_common/color.hpp>
#include <yabloc_common/pub_sub.hpp>

#include <cmath>
#include <pcl/ModelCoefficients.h>
#include <pcl/filters/crop_box.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>

#include <cmath>

namespace yabloc::ground_server
{
GroundServer::GroundServer(const rclcpp::NodeOptions & options)
Expand Down Expand Up @@ -230,8 +231,8 @@ GroundServer::GroundPlane GroundServer::estimate_ground(const Point & point)
const Eigen::Vector3f filt_normal = normal_filter_.update(normal);

GroundPlane plane;
plane.xyz = Eigen::Vector3f(static_cast<float>(point.x), static_cast<float>(point.y),
predicted_z);
plane.xyz =
Eigen::Vector3f(static_cast<float>(point.x), static_cast<float>(point.y), predicted_z);
plane.normal = filt_normal;

// Compute z value by intersection of estimated plane and orthogonal line
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,7 @@ pcl::PointCloud<pcl::PointXYZ> shrink_vertices(
{
Eigen::Vector3f center = std::accumulate(
vertices.begin(), vertices.end(), Eigen::Vector3f::Zero().eval(),
[](const Eigen::Vector3f& acc, const pcl::PointXYZ& p) { return acc + p.getVector3fMap(); }
);
[](const Eigen::Vector3f & acc, const pcl::PointXYZ & p) { return acc + p.getVector3fMap(); });
center /= static_cast<float>(vertices.size());

pcl::PointCloud<pcl::PointXYZ> dst_cloud;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ Ll2Decomposer::Ll2Decomposer(const rclcpp::NodeOptions & options) : Node("ll2_to
[this](const std::string & param_name, std::set<std::string> & labels) -> void {
this->template declare_parameter<std::vector<std::string>>(param_name);
auto label_array = get_parameter(param_name).as_string_array();
for (const auto& l : label_array) labels.insert(l);
for (const auto & l : label_array) labels.insert(l);
};

load_lanelet2_labels("road_marking_labels", road_marking_labels_);
Expand Down Expand Up @@ -86,7 +86,7 @@ pcl::PointCloud<pcl::PointXYZL> Ll2Decomposer::load_bounding_boxes(

for (const lanelet::ConstPolygon3d & polygon : polygons) {
if (!polygon.hasAttribute(lanelet::AttributeName::Type)) continue;
const lanelet::Attribute& attr = polygon.attribute(lanelet::AttributeName::Type);
const lanelet::Attribute & attr = polygon.attribute(lanelet::AttributeName::Type);
if (bounding_box_labels_.count(attr.value()) == 0) continue;

for (const lanelet::ConstPoint3d & p : polygon) {
Expand Down Expand Up @@ -151,7 +151,7 @@ lanelet::ConstLineStrings3d Ll2Decomposer::extract_specified_line_string(
lanelet::ConstLineStrings3d line_strings;
for (const lanelet::ConstLineString3d & line : line_string_layer) {
if (!line.hasAttribute(lanelet::AttributeName::Type)) continue;
const lanelet::Attribute& attr = line.attribute(lanelet::AttributeName::Type);
const lanelet::Attribute & attr = line.attribute(lanelet::AttributeName::Type);
if (visible_labels.count(attr.value()) == 0) continue;
line_strings.push_back(line);
}
Expand All @@ -164,7 +164,7 @@ lanelet::ConstPolygons3d Ll2Decomposer::extract_specified_polygon(
lanelet::ConstPolygons3d polygons;
for (const lanelet::ConstPolygon3d & polygon : polygon_layer) {
if (!polygon.hasAttribute(lanelet::AttributeName::Type)) continue;
const lanelet::Attribute& attr = polygon.attribute(lanelet::AttributeName::Type);
const lanelet::Attribute & attr = polygon.attribute(lanelet::AttributeName::Type);
if (visible_labels.count(attr.value()) == 0) continue;
polygons.push_back(polygon);
}
Expand Down
13 changes: 7 additions & 6 deletions localization/yabloc/yabloc_common/src/pose_conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@ Eigen::Affine3f pose_to_affine(const geometry_msgs::msg::Pose & pose)
{
const auto pos = pose.position;
const auto ori = pose.orientation;
Eigen::Translation3f t(static_cast<float>(pos.x), static_cast<float>(pos.y),
static_cast<float>(pos.z));
Eigen::Translation3f t(
static_cast<float>(pos.x), static_cast<float>(pos.y), static_cast<float>(pos.z));
Eigen::Quaternionf q(
static_cast<float>(ori.w), static_cast<float>(ori.x), static_cast<float>(ori.y),
static_cast<float>(ori.z));
Expand All @@ -49,10 +49,11 @@ Sophus::SE3f pose_to_se3(const geometry_msgs::msg::Pose & pose)
{
auto ori = pose.orientation;
auto pos = pose.position;
Eigen::Quaternionf q(static_cast<float>(ori.w), static_cast<float>(ori.x),
static_cast<float>(ori.y), static_cast<float>(ori.z));
Eigen::Vector3f t(static_cast<float>(pos.x), static_cast<float>(pos.y),
static_cast<float>(pos.z));
Eigen::Quaternionf q(
static_cast<float>(ori.w), static_cast<float>(ori.x), static_cast<float>(ori.y),
static_cast<float>(ori.z));
Eigen::Vector3f t(
static_cast<float>(pos.x), static_cast<float>(pos.y), static_cast<float>(pos.z));
return {q, t};
}

Expand Down

0 comments on commit 4b7e0eb

Please sign in to comment.