Skip to content

Commit

Permalink
fix(image_projection_based_fusion): set imagebuffersize (autowarefoun…
Browse files Browse the repository at this point in the history
…dation#820)

* fix: set imagebuffersize configured

Signed-off-by: suchang <chang.su@autocore.ai>

* ci(pre-commit): autofix

Co-authored-by: suchang <chang.su@autocore.ai>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
3 people authored and kosuke55 committed May 20, 2022
1 parent 5529f41 commit e04223e
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@ using sensor_msgs::msg::RegionOfInterest;
class Debugger
{
public:
explicit Debugger(rclcpp::Node * node_ptr, const std::size_t image_num);
explicit Debugger(
rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size);

void publishImage(const std::size_t image_id, const rclcpp::Time & stamp);

Expand All @@ -57,7 +58,7 @@ class Debugger
std::vector<image_transport::Subscriber> image_subs_;
std::vector<image_transport::Publisher> image_pubs_;
std::vector<boost::circular_buffer<sensor_msgs::msg::Image::ConstSharedPtr>> image_buffers_;
std::size_t image_buffer_size{5};
std::size_t image_buffer_size_;
};

} // namespace image_projection_based_fusion
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

<!-- 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 @@ -70,6 +71,7 @@

<!-- 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,7 @@

<!-- 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 @@ -70,6 +71,7 @@

<!-- debug -->
<param name="debug_mode" value="$(var debug_mode)"/>
<param name="image_buffer_size" value="$(var image_buffer_size)"/>
</node>
</group>
</launch>
7 changes: 5 additions & 2 deletions perception/image_projection_based_fusion/src/debugger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,12 @@ void drawRoiOnImage(

namespace image_projection_based_fusion
{
Debugger::Debugger(rclcpp::Node * node_ptr, const std::size_t image_num) : node_ptr_(node_ptr)
Debugger::Debugger(
rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size)
: node_ptr_(node_ptr)
{
image_buffers_.resize(image_num);
image_buffer_size_ = image_buffer_size;
for (std::size_t img_i = 0; img_i < image_num; ++img_i) {
auto sub = image_transport::create_subscription(
node_ptr, "input/image_raw" + std::to_string(img_i),
Expand All @@ -54,7 +57,7 @@ Debugger::Debugger(rclcpp::Node * node_ptr, const std::size_t image_num) : node_
auto pub =
image_transport::create_publisher(node_ptr, "output/image_raw" + std::to_string(img_i));
image_pubs_.push_back(pub);
image_buffers_.at(img_i).set_capacity(image_buffer_size);
image_buffers_.at(img_i).set_capacity(image_buffer_size_);
}
}

Expand Down
4 changes: 3 additions & 1 deletion perception/image_projection_based_fusion/src/fusion_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,9 @@ FusionNode<Msg>::FusionNode(const std::string & node_name, const rclcpp::NodeOpt

// debugger
if (declare_parameter("debug_mode", false)) {
debugger_ = std::make_shared<Debugger>(this, rois_number_);
std::size_t image_buffer_size =
static_cast<std::size_t>(declare_parameter("image_buffer_size", 15));
debugger_ = std::make_shared<Debugger>(this, rois_number_, image_buffer_size);
}
}

Expand Down

0 comments on commit e04223e

Please sign in to comment.