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

fix(pointcloud_preprocessor): organize input twist topic #5125

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 @@ -122,12 +122,16 @@
plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
name="concatenate_data",
namespace="plane_fitting",
remappings=[("output", "concatenated/pointcloud")],
remappings=[
("~/input/odom", "/localization/kinematic_state"),
("output", "concatenated/pointcloud"),
],
parameters=[
{
"input_topics": self.ground_segmentation_param["ransac_input_topics"],
"output_frame": LaunchConfiguration("base_frame"),
"timeout_sec": 1.0,
"input_twist_topic_type": "odom",

Check warning on line 134 in launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

GroundSegmentationPipeline.create_ransac_pipeline increases from 82 to 86 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
}
],
extra_arguments=[
Expand Down Expand Up @@ -432,11 +436,15 @@
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
name="concatenate_data",
remappings=[("output", output_topic)],
remappings=[
("~/input/odom", "/localization/kinematic_state"),
("output", output_topic),
],
parameters=[
{
"input_topics": input_topics,
"output_frame": LaunchConfiguration("base_frame"),
"input_twist_topic_type": "odom",
}
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
Expand All @@ -448,11 +456,15 @@
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
name="concatenate_no_ground_data",
remappings=[("output", output_topic)],
remappings=[
("~/input/odom", "/localization/kinematic_state"),
("output", output_topic),
],
parameters=[
{
"input_topics": input_topics,
"output_frame": LaunchConfiguration("base_frame"),
"input_twist_topic_type": "odom",
}
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
Expand Down
1 change: 1 addition & 0 deletions sensing/pointcloud_preprocessor/docs/concatenate-data.md
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ The figure below represents the reception time of each sensor data and how it is
| `timeout_sec` | double | 0.1 | tolerance of time to publish next pointcloud [s]<br>When this time limit is exceeded, the filter concatenates and publishes pointcloud, even if not all the point clouds are subscribed. |
| `input_offset` | vector of double | [] | This parameter can control waiting time for each input sensor pointcloud [s]. You must to set the same length of offsets with input pointclouds numbers. <br> For its tuning, please see [actual usage page](#how-to-tuning-timeout_sec-and-input_offset). |
| `publish_synchronized_pointcloud` | bool | false | If true, publish the time synchronized pointclouds. All input pointclouds are transformed and then re-published as message named `<original_msg_name>_synchronized`. |
| `input_twist_topic_type` | std::string | twist | Topic type for twist. Currently support `twist` or `odom`. |

## Actual Usage

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tier4_debug_msgs/msg/int32_stamped.hpp>
Expand All @@ -88,6 +89,7 @@ namespace pointcloud_preprocessor
{
using autoware_point_types::PointXYZI;
using point_cloud_msg_wrapper::PointCloud2Modifier;

/** \brief @b PointCloudConcatenateDataSynchronizerComponent is a special form of data
* synchronizer: it listens for a set of input PointCloud messages on the same topic,
* checks their timestamps, and concatenates their fields together into a single
Expand Down Expand Up @@ -131,10 +133,13 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
std::vector<rclcpp::Subscription<PointCloud2>::SharedPtr> filters_;

rclcpp::Subscription<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr sub_twist_;
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;

rclcpp::TimerBase::SharedPtr timer_;
diagnostic_updater::Updater updater_{this};

const std::string input_twist_topic_type_;

/** \brief Output TF frame the concatenated points should be transformed to. */
std::string output_frame_;

Expand Down Expand Up @@ -170,6 +175,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr,
const std::string & topic_name);
void twist_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr input);
void odom_callback(const nav_msgs::msg::Odometry::ConstSharedPtr input);
void timer_callback();

void checkConcatStatus(diagnostic_updater::DiagnosticStatusWrapper & stat);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,13 +38,17 @@
package=pkg,
plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
name="sync_and_concatenate_filter",
remappings=[("output", "points_raw/concatenated")],
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("output", "points_raw/concatenated"),
],
parameters=[
{
"input_topics": LaunchConfiguration("input_points_raw_list"),
"output_frame": LaunchConfiguration("tf_output_frame"),
"approximate_sync": True,
"publish_synchronized_pointcloud": False,
"input_twist_topic_type": "twist",

Check warning on line 51 in sensing/pointcloud_preprocessor/launch/preprocessor.launch.py

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

launch_setup increases from 104 to 108 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
}
],
)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check notice on line 1 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 6.09 to 5.55, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -69,7 +69,8 @@
{
PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchronizerComponent(
const rclcpp::NodeOptions & node_options)
: Node("point_cloud_concatenator_component", node_options)
: Node("point_cloud_concatenator_component", node_options),
input_twist_topic_type_(declare_parameter<std::string>("input_twist_topic_type", "twist"))

Check warning on line 73 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L73

Added line #L73 was not covered by tests
{
// initialize debug tool
{
Expand Down Expand Up @@ -164,10 +165,24 @@
filters_[d] = this->create_subscription<sensor_msgs::msg::PointCloud2>(
input_topics_[d], rclcpp::SensorDataQoS().keep_last(maximum_queue_size_), cb);
}
auto twist_cb = std::bind(
&PointCloudConcatenateDataSynchronizerComponent::twist_callback, this, std::placeholders::_1);
sub_twist_ = this->create_subscription<geometry_msgs::msg::TwistWithCovarianceStamped>(
"~/input/twist", rclcpp::QoS{100}, twist_cb);

if (input_twist_topic_type_ == "twist") {

Check warning on line 169 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L169

Added line #L169 was not covered by tests
auto twist_cb = std::bind(
&PointCloudConcatenateDataSynchronizerComponent::twist_callback, this,
std::placeholders::_1);
sub_twist_ = this->create_subscription<geometry_msgs::msg::TwistWithCovarianceStamped>(
"~/input/twist", rclcpp::QoS{100}, twist_cb);
} else if (input_twist_topic_type_ == "odom") {

Check warning on line 175 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L173-L175

Added lines #L173 - L175 were not covered by tests
auto odom_cb = std::bind(
&PointCloudConcatenateDataSynchronizerComponent::odom_callback, this,
std::placeholders::_1);
sub_odom_ = this->create_subscription<nav_msgs::msg::Odometry>(
"~/input/odom", rclcpp::QoS{100}, odom_cb);

Check warning on line 180 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L179-L180

Added lines #L179 - L180 were not covered by tests
} else {
RCLCPP_ERROR_STREAM(

Check warning on line 182 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L182

Added line #L182 was not covered by tests
get_logger(), "input_twist_topic_type is invalid: " << input_twist_topic_type_);
throw std::runtime_error("input_twist_topic_type is invalid: " + input_twist_topic_type_);

Check warning on line 184 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L184

Added line #L184 was not covered by tests
}

Check notice on line 185 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Method

PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchronizerComponent is no longer above the threshold for cyclomatic complexity. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
}

// Transformed Raw PointCloud2 Publisher
Expand Down Expand Up @@ -227,8 +242,19 @@
PointCloudConcatenateDataSynchronizerComponent::computeTransformToAdjustForOldTimestamp(
const rclcpp::Time & old_stamp, const rclcpp::Time & new_stamp)
{
// return identity if no twist is available or old_stamp is newer than new_stamp
if (twist_ptr_queue_.empty() || old_stamp > new_stamp) {
// return identity if no twist is available
if (twist_ptr_queue_.empty()) {
RCLCPP_WARN_STREAM_THROTTLE(

Check warning on line 247 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L246-L247

Added lines #L246 - L247 were not covered by tests
get_logger(), *get_clock(), std::chrono::milliseconds(10000).count(),
"No twist is available. Please confirm twist topic and timestamp");
return Eigen::Matrix4f::Identity();
}

// return identity if old_stamp is newer than new_stamp
if (old_stamp > new_stamp) {
RCLCPP_WARN_STREAM_THROTTLE(

Check warning on line 255 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L254-L255

Added lines #L254 - L255 were not covered by tests
get_logger(), *get_clock(), std::chrono::milliseconds(10000).count(),
"old_stamp is newer than new_stamp,");
return Eigen::Matrix4f::Identity();
}

Expand Down Expand Up @@ -555,9 +581,35 @@
auto twist_ptr = std::make_shared<geometry_msgs::msg::TwistStamped>();
twist_ptr->header = input->header;
twist_ptr->twist = input->twist.twist;
twist_ptr_queue_.push_back(twist_ptr);
}

Check warning on line 585 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Code Duplication

The module contains 2 functions with similar structure: PointCloudConcatenateDataSynchronizerComponent::odom_callback,PointCloudConcatenateDataSynchronizerComponent::twist_callback. Avoid duplicated, aka copy-pasted, code inside the module. More duplication lowers the code health.

void PointCloudConcatenateDataSynchronizerComponent::odom_callback(

Check warning on line 587 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L587

Added line #L587 was not covered by tests
const nav_msgs::msg::Odometry::ConstSharedPtr input)
{
// if rosbag restart, clear buffer
if (!twist_ptr_queue_.empty()) {
if (rclcpp::Time(twist_ptr_queue_.front()->header.stamp) > rclcpp::Time(input->header.stamp)) {
twist_ptr_queue_.clear();

Check warning on line 593 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L591-L593

Added lines #L591 - L593 were not covered by tests
}
}

// pop old data
while (!twist_ptr_queue_.empty()) {
if (
rclcpp::Time(twist_ptr_queue_.front()->header.stamp) + rclcpp::Duration::from_seconds(1.0) >
rclcpp::Time(input->header.stamp)) {

Check warning on line 601 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L598-L601

Added lines #L598 - L601 were not covered by tests
break;
}
twist_ptr_queue_.pop_front();

Check warning on line 604 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L604

Added line #L604 was not covered by tests
}

auto twist_ptr = std::make_shared<geometry_msgs::msg::TwistStamped>();
twist_ptr->header = input->header;
twist_ptr->twist = input->twist.twist;

Check warning on line 609 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

PointCloudConcatenateDataSynchronizerComponent::odom_callback has 2 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
twist_ptr_queue_.push_back(twist_ptr);
}

Check warning on line 611 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L609-L611

Added lines #L609 - L611 were not covered by tests

void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus(
diagnostic_updater::DiagnosticStatusWrapper & stat)
{
Expand Down
Loading