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(map_tf_generator): apply static analysis #7350

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 @@ -18,7 +18,7 @@
#include <random>
#include <vector>

std::vector<size_t> UniformRandom(const size_t max_exclusive, const size_t n)
std::vector<size_t> inline uniform_random(const size_t max_exclusive, const size_t n)
{
std::default_random_engine generator;
std::uniform_int_distribution<size_t> distribution(0, max_exclusive - 1);
Expand Down
48 changes: 24 additions & 24 deletions map/map_tf_generator/src/pcd_map_tf_generator_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,22 +26,22 @@

#include <memory>
#include <string>
#include <variant>

constexpr size_t N_SAMPLES = 20;
constexpr size_t n_samples = 20;

class PcdMapTFGeneratorNode : public rclcpp::Node
{
public:
using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
explicit PcdMapTFGeneratorNode(const rclcpp::NodeOptions & options)
: Node("pcd_map_tf_generator", options)
: Node("pcd_map_tf_generator", options),
map_frame_(declare_parameter<std::string>("map_frame")),
viewer_frame_(declare_parameter<std::string>("viewer_frame"))

Check warning on line 40 in map/map_tf_generator/src/pcd_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/pcd_map_tf_generator_node.cpp#L38-L40

Added lines #L38 - L40 were not covered by tests
{
map_frame_ = declare_parameter<std::string>("map_frame");
viewer_frame_ = declare_parameter<std::string>("viewer_frame");

sub_ = create_subscription<sensor_msgs::msg::PointCloud2>(
"pointcloud_map", rclcpp::QoS{1}.transient_local(),
std::bind(&PcdMapTFGeneratorNode::onPointCloud, this, std::placeholders::_1));
std::bind(&PcdMapTFGeneratorNode::on_point_cloud, this, std::placeholders::_1));

Check warning on line 44 in map/map_tf_generator/src/pcd_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/pcd_map_tf_generator_node.cpp#L44

Added line #L44 was not covered by tests

static_broadcaster_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);
}
Expand All @@ -53,7 +53,7 @@

std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_broadcaster_;

void onPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr clouds_ros)
void on_point_cloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr clouds_ros)

Check warning on line 56 in map/map_tf_generator/src/pcd_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/pcd_map_tf_generator_node.cpp#L56

Added line #L56 was not covered by tests
{
// fix random seed to produce the same viewer position every time
// 3939 is just the author's favorite number
Expand All @@ -62,32 +62,32 @@
PointCloud clouds;
pcl::fromROSMsg<pcl::PointXYZ>(*clouds_ros, clouds);

const std::vector<size_t> indices = UniformRandom(clouds.size(), N_SAMPLES);
const std::vector<size_t> indices = uniform_random(clouds.size(), n_samples);

Check warning on line 65 in map/map_tf_generator/src/pcd_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/pcd_map_tf_generator_node.cpp#L65

Added line #L65 was not covered by tests
double coordinate[3] = {0, 0, 0};
for (const auto i : indices) {
coordinate[0] += clouds.points[i].x;
coordinate[1] += clouds.points[i].y;
coordinate[2] += clouds.points[i].z;
}
coordinate[0] = coordinate[0] / indices.size();
coordinate[1] = coordinate[1] / indices.size();
coordinate[2] = coordinate[2] / indices.size();

geometry_msgs::msg::TransformStamped static_transformStamped;
static_transformStamped.header.stamp = this->now();
static_transformStamped.header.frame_id = map_frame_;
static_transformStamped.child_frame_id = viewer_frame_;
static_transformStamped.transform.translation.x = coordinate[0];
static_transformStamped.transform.translation.y = coordinate[1];
static_transformStamped.transform.translation.z = coordinate[2];
coordinate[0] = coordinate[0] / static_cast<double>(indices.size());
coordinate[1] = coordinate[1] / static_cast<double>(indices.size());
coordinate[2] = coordinate[2] / static_cast<double>(indices.size());

Check warning on line 74 in map/map_tf_generator/src/pcd_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/pcd_map_tf_generator_node.cpp#L72-L74

Added lines #L72 - L74 were not covered by tests

geometry_msgs::msg::TransformStamped static_transform_stamped;
static_transform_stamped.header.stamp = this->now();
static_transform_stamped.header.frame_id = map_frame_;
static_transform_stamped.child_frame_id = viewer_frame_;
static_transform_stamped.transform.translation.x = coordinate[0];
static_transform_stamped.transform.translation.y = coordinate[1];
static_transform_stamped.transform.translation.z = coordinate[2];

Check warning on line 82 in map/map_tf_generator/src/pcd_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/pcd_map_tf_generator_node.cpp#L76-L82

Added lines #L76 - L82 were not covered by tests
tf2::Quaternion quat;
quat.setRPY(0, 0, 0);
static_transformStamped.transform.rotation.x = quat.x();
static_transformStamped.transform.rotation.y = quat.y();
static_transformStamped.transform.rotation.z = quat.z();
static_transformStamped.transform.rotation.w = quat.w();
static_transform_stamped.transform.rotation.x = quat.x();
static_transform_stamped.transform.rotation.y = quat.y();
static_transform_stamped.transform.rotation.z = quat.z();
static_transform_stamped.transform.rotation.w = quat.w();

Check warning on line 88 in map/map_tf_generator/src/pcd_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/pcd_map_tf_generator_node.cpp#L85-L88

Added lines #L85 - L88 were not covered by tests

static_broadcaster_->sendTransform(static_transformStamped);
static_broadcaster_->sendTransform(static_transform_stamped);

Check warning on line 90 in map/map_tf_generator/src/pcd_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/pcd_map_tf_generator_node.cpp#L90

Added line #L90 was not covered by tests

RCLCPP_INFO_STREAM(
get_logger(), "broadcast static tf. map_frame:"
Expand Down
41 changes: 20 additions & 21 deletions map/map_tf_generator/src/vector_map_tf_generator_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,14 +29,13 @@
{
public:
explicit VectorMapTFGeneratorNode(const rclcpp::NodeOptions & options)
: Node("vector_map_tf_generator", options)
: Node("vector_map_tf_generator", options),
map_frame_(declare_parameter<std::string>("map_frame")),
viewer_frame_(declare_parameter<std::string>("viewer_frame"))

Check warning on line 34 in map/map_tf_generator/src/vector_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/vector_map_tf_generator_node.cpp#L32-L34

Added lines #L32 - L34 were not covered by tests
{
map_frame_ = declare_parameter<std::string>("map_frame");
viewer_frame_ = declare_parameter<std::string>("viewer_frame");

sub_ = create_subscription<autoware_map_msgs::msg::LaneletMapBin>(
"vector_map", rclcpp::QoS{1}.transient_local(),
std::bind(&VectorMapTFGeneratorNode::onVectorMap, this, std::placeholders::_1));
std::bind(&VectorMapTFGeneratorNode::on_vector_map, this, std::placeholders::_1));

Check warning on line 38 in map/map_tf_generator/src/vector_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/vector_map_tf_generator_node.cpp#L38

Added line #L38 was not covered by tests

static_broadcaster_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);
}
Expand All @@ -49,7 +48,7 @@
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_broadcaster_;
std::shared_ptr<lanelet::LaneletMap> lanelet_map_ptr_;

void onVectorMap(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg)
void on_vector_map(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg)

Check warning on line 51 in map/map_tf_generator/src/vector_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/vector_map_tf_generator_node.cpp#L51

Added line #L51 was not covered by tests
{
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map_ptr_);
Expand All @@ -66,27 +65,27 @@
points_z.push_back(point_z);
}
const double coordinate_x =
std::accumulate(points_x.begin(), points_x.end(), 0.0) / points_x.size();
std::accumulate(points_x.begin(), points_x.end(), 0.0) / static_cast<double>(points_x.size());

Check warning on line 68 in map/map_tf_generator/src/vector_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/vector_map_tf_generator_node.cpp#L68

Added line #L68 was not covered by tests
const double coordinate_y =
std::accumulate(points_y.begin(), points_y.end(), 0.0) / points_y.size();
std::accumulate(points_y.begin(), points_y.end(), 0.0) / static_cast<double>(points_y.size());

Check warning on line 70 in map/map_tf_generator/src/vector_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/vector_map_tf_generator_node.cpp#L70

Added line #L70 was not covered by tests
const double coordinate_z =
std::accumulate(points_z.begin(), points_z.end(), 0.0) / points_z.size();
std::accumulate(points_z.begin(), points_z.end(), 0.0) / static_cast<double>(points_z.size());

Check warning on line 72 in map/map_tf_generator/src/vector_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/vector_map_tf_generator_node.cpp#L72

Added line #L72 was not covered by tests

geometry_msgs::msg::TransformStamped static_transformStamped;
static_transformStamped.header.stamp = this->now();
static_transformStamped.header.frame_id = map_frame_;
static_transformStamped.child_frame_id = viewer_frame_;
static_transformStamped.transform.translation.x = coordinate_x;
static_transformStamped.transform.translation.y = coordinate_y;
static_transformStamped.transform.translation.z = coordinate_z;
geometry_msgs::msg::TransformStamped static_transform_stamped;
static_transform_stamped.header.stamp = this->now();
static_transform_stamped.header.frame_id = map_frame_;
static_transform_stamped.child_frame_id = viewer_frame_;
static_transform_stamped.transform.translation.x = coordinate_x;
static_transform_stamped.transform.translation.y = coordinate_y;
static_transform_stamped.transform.translation.z = coordinate_z;

Check warning on line 80 in map/map_tf_generator/src/vector_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/vector_map_tf_generator_node.cpp#L74-L80

Added lines #L74 - L80 were not covered by tests
tf2::Quaternion quat;
quat.setRPY(0, 0, 0);
static_transformStamped.transform.rotation.x = quat.x();
static_transformStamped.transform.rotation.y = quat.y();
static_transformStamped.transform.rotation.z = quat.z();
static_transformStamped.transform.rotation.w = quat.w();
static_transform_stamped.transform.rotation.x = quat.x();
static_transform_stamped.transform.rotation.y = quat.y();
static_transform_stamped.transform.rotation.z = quat.z();
static_transform_stamped.transform.rotation.w = quat.w();

Check warning on line 86 in map/map_tf_generator/src/vector_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/vector_map_tf_generator_node.cpp#L83-L86

Added lines #L83 - L86 were not covered by tests

static_broadcaster_->sendTransform(static_transformStamped);
static_broadcaster_->sendTransform(static_transform_stamped);

Check warning on line 88 in map/map_tf_generator/src/vector_map_tf_generator_node.cpp

View check run for this annotation

Codecov / codecov/patch

map/map_tf_generator/src/vector_map_tf_generator_node.cpp#L88

Added line #L88 was not covered by tests

RCLCPP_INFO_STREAM(
get_logger(), "broadcast static tf. map_frame:"
Expand Down
6 changes: 3 additions & 3 deletions map/map_tf_generator/test/test_uniform_random.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,10 @@ using testing::Each;
using testing::Ge;
using testing::Lt;

TEST(UniformRandom, UniformRandom)
TEST(uniform_random, uniform_random)
{
{
const std::vector<size_t> random = UniformRandom(4, 0);
const std::vector<size_t> random = uniform_random(4, 0);
ASSERT_EQ(random.size(), static_cast<size_t>(0));
}

Expand All @@ -35,7 +35,7 @@ TEST(UniformRandom, UniformRandom)
const size_t max_exclusive = 4;

for (int i = 0; i < 50; i++) {
const std::vector<size_t> random = UniformRandom(4, 10);
const std::vector<size_t> random = uniform_random(4, 10);
ASSERT_EQ(random.size(), 10U);
ASSERT_THAT(random, Each(AllOf(Ge(min_inclusive), Lt(max_exclusive)))); // in range [0, 4)
}
Expand Down
Loading