Skip to content

Commit

Permalink
update qos and add detector_hue launch
Browse files Browse the repository at this point in the history
  • Loading branch information
Ar-Ray-code committed Feb 16, 2024
1 parent 09fca7c commit 78f6a9e
Show file tree
Hide file tree
Showing 2 changed files with 46 additions and 1 deletion.
45 changes: 45 additions & 0 deletions detector2d_bringup/launch/detector_hue.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode

def generate_launch_description():
container = ComposableNodeContainer(
name='detector_container',
namespace='',
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=[
# ComposableNode(
# package='realsense2_camera',
# plugin='realsense2_camera::RealSenseNodeFactory',
# name='realsense2_camera',
# namespace='',
# parameters=[{
# 'align_depth.enable': True,
# 'enable_color': True,
# 'enable_depth': True
# }]
# ),
ComposableNode(
package='detector2d_node',
plugin='detector2d_node::Detector2dNode',
name='detector2d_node',
namespace='',
parameters=[{
'load_target_plugin': 'detector2d_plugins::PanelSimpleDetector',
'debug': True
}],
remappings=[
('image_raw', 'blue/camera/image_raw')
]
)
]
)

return LaunchDescription([
container
])
2 changes: 1 addition & 1 deletion detector2d_node/src/detector2d_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ Detector2dNode::Detector2dNode(const rclcpp::NodeOptions & options)
this->pose_pub_ = this->create_publisher<vision_msgs::msg::Detection2DArray>(
"positions", 1);
this->image_sub_ = this->create_subscription<sensor_msgs::msg::Image>(
"image_raw", 1, std::bind(&Detector2dNode::image_callback, this, std::placeholders::_1));
"image_raw", rclcpp::SensorDataQoS(), std::bind(&Detector2dNode::image_callback, this, std::placeholders::_1));
}

void Detector2dNode::image_callback(const sensor_msgs::msg::Image::SharedPtr msg)
Expand Down

0 comments on commit 78f6a9e

Please sign in to comment.