Skip to content

Commit

Permalink
refactor: update funsion node configuration
Browse files Browse the repository at this point in the history
Signed-off-by: ktro2828 <[email protected]>
  • Loading branch information
ktro2828 committed Sep 12, 2023
1 parent 22a9f04 commit 7823ae4
Show file tree
Hide file tree
Showing 5 changed files with 53 additions and 26 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,10 @@
input_offset_ms: [61.67, 111.67, 45.0, 28.33, 78.33, 95.0]
timeout_ms: 70.0
match_threshold_ms: 50.0
image_buffer_size: 15
filter_scope_minx: -100.0
filter_scope_miny: -100.0
filter_scope_minz: -100.0
filter_scope_maxx: 100.0
filter_scope_maxy: 100.0
filter_scope_maxz: 100.0
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
<launch>
<arg name="input/rois_number" default="1"/>
<arg name="input/rois0" default="rois0"/>
<arg name="input/camera_info0" default="/camera_info0"/>
<arg name="input/rois1" default="rois1"/>
Expand Down Expand Up @@ -27,13 +26,6 @@
<!-- debug -->
<!-- cspell: ignore minx, maxx, miny, maxy, minz, maxz -->
<arg name="debug_mode" default="false"/>
<arg name="filter_scope_minx" default="-100"/>
<arg name="filter_scope_maxx" default="100"/>
<arg name="filter_scope_miny" default="-100"/>
<arg name="filter_scope_maxy" default="100"/>
<arg name="filter_scope_minz" default="-100"/>
<arg name="filter_scope_maxz" default="100"/>
<arg name="image_buffer_size" default="15"/>
<arg name="input/image0" default="/image_raw0"/>
<arg name="input/image1" default="/image_raw1"/>
<arg name="input/image2" default="/image_raw2"/>
Expand Down Expand Up @@ -78,13 +70,6 @@

<!-- debug -->
<param name="debug_mode" value="$(var debug_mode)"/>
<param name="filter_scope_minx" value="$(var filter_scope_minx)"/>
<param name="filter_scope_maxx" value="$(var filter_scope_maxx)"/>
<param name="filter_scope_miny" value="$(var filter_scope_miny)"/>
<param name="filter_scope_maxy" value="$(var filter_scope_maxy)"/>
<param name="filter_scope_minz" value="$(var filter_scope_minz)"/>
<param name="filter_scope_maxz" value="$(var filter_scope_maxz)"/>
<param name="image_buffer_size" value="$(var image_buffer_size)"/>
</node>
</group>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@

<!-- debug -->
<arg name="debug_mode" default="false"/>
<arg name="image_buffer_size" default="15"/>
<arg name="input/image0" default="/image_raw0"/>
<arg name="input/image1" default="/image_raw1"/>
<arg name="input/image2" default="/image_raw2"/>
Expand Down Expand Up @@ -72,7 +71,6 @@

<!-- debug -->
<param name="debug_mode" value="$(var debug_mode)"/>
<param name="image_buffer_size" value="$(var image_buffer_size)"/>
</node>
</group>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,42 @@
"default": 50.0,
"minimum": 0.0,
"maximum": 100.0
},
"image_buffer_size": {
"type": "integer",
"description": "The number of image buffer size for debug.",
"default": 15,
"minimum": 1
},
"filter_scope_minx": {
"type": "number",
"description": "Minimum x position to be considered for debug [m].",
"default": -100.0
},
"filter_scope_miny": {
"type": "number",
"description": "Minimum y position to be considered for debug [m].",
"default": -100.0
},
"filter_scope_minz": {
"type": "number",
"description": "Minimum z position to be considered for debug [m].",
"default": -100.0
},
"filter_scope_maxx": {
"type": "number",
"description": "Maximum x position to be considered for debug [m].",
"default": 100.0
},
"filter_scope_maxy": {
"type": "number",
"description": "Maximum y position to be considered for debug [m].",
"default": 100.0
},
"filter_scope_maxz": {
"type": "number",
"description": "Maximum z position [m].",
"default": 100.0
}
}
}
Expand Down
19 changes: 10 additions & 9 deletions perception/image_projection_based_fusion/src/fusion_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ FusionNode<Msg, ObjType>::FusionNode(
: Node(node_name, options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_)
{
// set rois_number
rois_number_ = static_cast<std::size_t>(declare_parameter("rois_number", 1));
rois_number_ = static_cast<std::size_t>(declare_parameter<int32_t>("rois_number"));
if (rois_number_ < 1) {
RCLCPP_WARN(
this->get_logger(), "minimum rois_number is 1. current rois_number is %zu", rois_number_);
Expand Down Expand Up @@ -80,7 +80,7 @@ FusionNode<Msg, ObjType>::FusionNode(
"/sensing/camera/camera" + std::to_string(roi_i) + "/image_rect_color");
}

input_offset_ms_ = declare_parameter("input_offset_ms", std::vector<double>{});
input_offset_ms_ = declare_parameter<std::vector<double>>("input_offset_ms");
if (!input_offset_ms_.empty() && rois_number_ != input_offset_ms_.size()) {
throw std::runtime_error("The number of offsets does not match the number of topics.");
}
Expand Down Expand Up @@ -122,7 +122,7 @@ FusionNode<Msg, ObjType>::FusionNode(
// debugger
if (declare_parameter("debug_mode", false)) {
std::size_t image_buffer_size =
static_cast<std::size_t>(declare_parameter("image_buffer_size", 15));
static_cast<std::size_t>(declare_parameter<int32_t>("image_buffer_size"));
debugger_ =
std::make_shared<Debugger>(this, rois_number_, image_buffer_size, input_camera_topics_);
}
Expand All @@ -136,14 +136,15 @@ FusionNode<Msg, ObjType>::FusionNode(
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");
}

// cspell: ignore minx, maxx, miny, maxy, minz, maxz
// FIXME: use min_x instead of minx
filter_scope_minx_ = declare_parameter("filter_scope_minx", -100);
filter_scope_maxx_ = declare_parameter("filter_scope_maxx", 100);
filter_scope_miny_ = declare_parameter("filter_scope_miny", -100);
filter_scope_maxy_ = declare_parameter("filter_scope_maxy", 100);
filter_scope_minz_ = declare_parameter("filter_scope_minz", -100);
filter_scope_maxz_ = declare_parameter("filter_scope_maxz", 100);
filter_scope_minx_ = declare_parameter<double>("filter_scope_minx");
filter_scope_maxx_ = declare_parameter<double>("filter_scope_maxx");
filter_scope_miny_ = declare_parameter<double>("filter_scope_miny");
filter_scope_maxy_ = declare_parameter<double>("filter_scope_maxy");
filter_scope_minz_ = declare_parameter<double>("filter_scope_minz");
filter_scope_maxz_ = declare_parameter<double>("filter_scope_maxz");
}

template <class Msg, class Obj>
Expand Down

0 comments on commit 7823ae4

Please sign in to comment.