Skip to content

Commit

Permalink
chroe: refactor collectorinfo structure
Browse files Browse the repository at this point in the history
Signed-off-by: vividf <[email protected]>
  • Loading branch information
vividf committed Jan 6, 2025
1 parent 9523a3b commit d01eba8
Show file tree
Hide file tree
Showing 5 changed files with 34 additions and 43 deletions.
Original file line number Diff line number Diff line change
@@ -1,12 +1,21 @@
/**:
ros__parameters:
output_frame: base_link
has_static_tf_only: true
debug_mode: false
has_static_tf_only: false
rosbag_length: 10.0
maximum_queue_size: 5
timeout_sec: 0.2
is_motion_compensated: true
publish_synchronized_pointcloud: true
keep_input_frame_in_synchronized_pointcloud: true
publish_previous_but_late_pointcloud: false
synchronized_pointcloud_postfix: pointcloud
input_twist_topic_type: twist
input_topics: [
"/sensing/lidar/left/pointcloud_before_sync",
"/sensing/lidar/right/pointcloud_before_sync",
"/sensing/lidar/top/pointcloud_before_sync"
"/sensing/lidar/top/pointcloud_before_sync",
"/sensing/lidar/left/pointcloud_before_sync",
]
max_queue_size: 5
timeout_sec: 0.033
input_offset: [0.0 ,0.0 ,0.0]
output_frame: base_link
matching_strategy:
type: naive
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@

#include <memory>
#include <string>
#include <tuple>
#include <unordered_map>

namespace autoware::pointcloud_preprocessor
Expand All @@ -27,32 +26,26 @@ namespace autoware::pointcloud_preprocessor
class PointCloudConcatenateDataSynchronizerComponent;
class CombineCloudHandler;

enum class CollectorStrategyType { Naive, Advanced };

struct CollectorInfoBase
{
virtual ~CollectorInfoBase() = default;
[[nodiscard]] virtual CollectorStrategyType getStrategyType() const = 0;
};

struct NaiveCollectorInfo : public CollectorInfoBase
{
double timestamp{0.0};
double timestamp;

[[nodiscard]] CollectorStrategyType getStrategyType() const override
{
return CollectorStrategyType::Naive;
}
explicit NaiveCollectorInfo(double timestamp = 0.0) : timestamp(timestamp) {}
};

struct AdvancedCollectorInfo : public CollectorInfoBase
{
double timestamp{0.0};
double noise_window{0.0};
double timestamp;
double noise_window;

[[nodiscard]] CollectorStrategyType getStrategyType() const override
explicit AdvancedCollectorInfo(double timestamp = 0.0, double noise_window = 0.0)
: timestamp(timestamp), noise_window(noise_window)
{
return CollectorStrategyType::Advanced;
}
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,6 @@ class CollectorMatchingStrategy
const MatchingParams & params) const = 0;
virtual void set_collector_info(
std::shared_ptr<CloudCollector> & collector, const MatchingParams & matching_params) = 0;

protected:
CollectorStrategyType strategy_type_;
};

class NaiveMatchingStrategy : public CollectorMatchingStrategy
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,18 +128,14 @@ void CloudCollector::show_debug_message()
log_stream << "Collector's concatenate callback time: "
<< ros2_parent_node_->get_clock()->now().seconds() << " seconds\n";

if (collector_info_) {
if (collector_info_->getStrategyType() == CollectorStrategyType::Advanced) {
auto advanced_info = std::dynamic_pointer_cast<AdvancedCollectorInfo>(collector_info_);
log_stream << "Advanced strategy:\n Collector's reference time min: "
<< advanced_info->timestamp - advanced_info->noise_window
<< " to max: " << advanced_info->timestamp + advanced_info->noise_window
<< " seconds\n";
} else if (collector_info_->getStrategyType() == CollectorStrategyType::Naive) {
auto naive_info = std::dynamic_pointer_cast<NaiveCollectorInfo>(collector_info_);
log_stream << "Naive strategy:\n Collector's timestamp: " << naive_info->timestamp
<< " seconds\n";
}
if (auto advanced_info = std::dynamic_pointer_cast<AdvancedCollectorInfo>(collector_info_)) {
log_stream << "Advanced strategy:\n Collector's reference time min: "
<< advanced_info->timestamp - advanced_info->noise_window
<< " to max: " << advanced_info->timestamp + advanced_info->noise_window
<< " seconds\n";
} else if (auto naive_info = std::dynamic_pointer_cast<NaiveCollectorInfo>(collector_info_)) {
log_stream << "Naive strategy:\n Collector's timestamp: " << naive_info->timestamp
<< " seconds\n";
}

log_stream << "Time until trigger: " << (time_until_trigger.count() / 1e9) << " seconds\n";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@ namespace autoware::pointcloud_preprocessor

NaiveMatchingStrategy::NaiveMatchingStrategy(rclcpp::Node & node)
{
strategy_type_ = CollectorStrategyType::Naive;
RCLCPP_INFO(node.get_logger(), "Utilize naive matching strategy");
}

Expand Down Expand Up @@ -58,15 +57,13 @@ std::optional<std::shared_ptr<CloudCollector>> NaiveMatchingStrategy::match_clou
void NaiveMatchingStrategy::set_collector_info(
std::shared_ptr<CloudCollector> & collector, const MatchingParams & matching_params)
{
auto info = std::make_shared<NaiveCollectorInfo>();
info->timestamp = matching_params.cloud_arrival_time;
auto info = std::make_shared<NaiveCollectorInfo>(matching_params.cloud_arrival_time);
collector->set_info(info);
}

AdvancedMatchingStrategy::AdvancedMatchingStrategy(
rclcpp::Node & node, std::vector<std::string> input_topics)
{
strategy_type_ = CollectorStrategyType::Advanced;
auto lidar_timestamp_offsets =
node.declare_parameter<std::vector<double>>("matching_strategy.lidar_timestamp_offsets");
auto lidar_timestamp_noise_window =
Expand Down Expand Up @@ -114,10 +111,9 @@ std::optional<std::shared_ptr<CloudCollector>> AdvancedMatchingStrategy::match_c
void AdvancedMatchingStrategy::set_collector_info(
std::shared_ptr<CloudCollector> & collector, const MatchingParams & matching_params)
{
auto info = std::make_shared<AdvancedCollectorInfo>();
info->timestamp =
matching_params.cloud_timestamp - topic_to_offset_map_[matching_params.topic_name];
info->noise_window = topic_to_noise_window_map_[matching_params.topic_name];
auto info = std::make_shared<AdvancedCollectorInfo>(
matching_params.cloud_timestamp - topic_to_offset_map_[matching_params.topic_name],
topic_to_noise_window_map_[matching_params.topic_name]);
collector->set_info(info);
}

Expand Down

0 comments on commit d01eba8

Please sign in to comment.