Skip to content

Commit

Permalink
Merge branch 'rolling' into ahcorde/fix/paremeters/when_using_component
Browse files Browse the repository at this point in the history
  • Loading branch information
ahcorde authored Jan 17, 2024
2 parents 547d07b + 24dec52 commit 00f7b88
Show file tree
Hide file tree
Showing 12 changed files with 28 additions and 5 deletions.
1 change: 1 addition & 0 deletions camera_calibration/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
<maintainer email="[email protected]">Vincent Rabaud</maintainer>
<maintainer email="[email protected]">Joshua Whitley</maintainer>
<maintainer email="[email protected]">Jacob Perron</maintainer>
<maintainer email="[email protected]">Michael Ferguson</maintainer>

<license>BSD</license>
<url type="website">https://index.ros.org/p/camera_calibration/github-ros-perception-image_pipeline/</url>
Expand Down
1 change: 1 addition & 0 deletions depth_image_proc/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
<maintainer email="[email protected]">Joshua Whitley</maintainer>
<maintainer email="[email protected]">Chris Ye</maintainer>
<maintainer email="[email protected]">Jacob Perron</maintainer>
<maintainer email="[email protected]">Michael Ferguson</maintainer>

<license>BSD</license>
<url type="website">https://index.ros.org/p/depth_image_proc/github-ros-perception-image_pipeline/</url>
Expand Down
19 changes: 17 additions & 2 deletions depth_image_proc/src/point_cloud_xyzrgb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,12 +109,27 @@ void PointCloudXyzrgbNode::connectCb()
std::string depth_image_transport_param = "depth_image_transport";
image_transport::TransportHints depth_hints(this, "raw", depth_image_transport_param);

rclcpp::SubscriptionOptions sub_opts;
// Update the subscription options to allow reconfigurable qos settings.
sub_opts.qos_overriding_options = rclcpp::QosOverridingOptions {
{
// Here all policies that are desired to be reconfigurable are listed.
rclcpp::QosPolicyKind::Depth,
rclcpp::QosPolicyKind::Durability,
rclcpp::QosPolicyKind::History,
rclcpp::QosPolicyKind::Reliability,
}};

// depth image can use different transport.(e.g. compressedDepth)
sub_depth_.subscribe(this, "depth_registered/image_rect", depth_hints.getTransport());
sub_depth_.subscribe(
this, "depth_registered/image_rect",
depth_hints.getTransport(), rmw_qos_profile_default, sub_opts);

// rgb uses normal ros transport hints.
image_transport::TransportHints hints(this, "raw");
sub_rgb_.subscribe(this, "rgb/image_rect_color", hints.getTransport());
sub_rgb_.subscribe(
this, "rgb/image_rect_color",
hints.getTransport(), rmw_qos_profile_default, sub_opts);
sub_info_.subscribe(this, "rgb/camera_info");
}
}
Expand Down
1 change: 1 addition & 0 deletions image_pipeline/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<maintainer email="[email protected]">Vincent Rabaud</maintainer>
<maintainer email="[email protected]">Joshua Whitley</maintainer>
<maintainer email="[email protected]">Jacob Perron</maintainer>
<maintainer email="[email protected]">Michael Ferguson</maintainer>

<license>BSD</license>
<url type="website">https://index.ros.org/p/image_pipeline/github-ros-perception-image_pipeline/</url>
Expand Down
1 change: 1 addition & 0 deletions image_proc/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<maintainer email="[email protected]">Vincent Rabaud</maintainer>
<maintainer email="[email protected]">Joshua Whitley</maintainer>
<maintainer email="[email protected]">Jacob Perron</maintainer>
<maintainer email="[email protected]">Michael Ferguson</maintainer>

<license>BSD</license>
<url type="website">https://index.ros.org/p/image_proc/github-ros-perception-image_pipeline/</url>
Expand Down
1 change: 1 addition & 0 deletions image_publisher/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<maintainer email="[email protected]">Joshua Whitley</maintainer>
<maintainer email="[email protected]">Chris Ye</maintainer>
<maintainer email="[email protected]">Jacob Perron</maintainer>
<maintainer email="[email protected]">Michael Ferguson</maintainer>

<license>BSD</license>
<url type="website">https://index.ros.org/p/image_publisher/github-ros-perception-image_pipeline/</url>
Expand Down
1 change: 1 addition & 0 deletions image_rotate/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<maintainer email="[email protected]">Vincent Rabaud</maintainer>
<maintainer email="[email protected]">Joshua Whitley</maintainer>
<maintainer email="[email protected]">Jacob Perron</maintainer>
<maintainer email="[email protected]">Michael Ferguson</maintainer>

<license>BSD</license>
<url type="website">https://index.ros.org/p/image_rotate/github-ros-perception-image_pipeline/</url>
Expand Down
1 change: 1 addition & 0 deletions image_view/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
<maintainer email="[email protected]">Vincent Rabaud</maintainer>
<maintainer email="[email protected]">Joshua Whitley</maintainer>
<maintainer email="[email protected]">Jacob Perron</maintainer>
<maintainer email="[email protected]">Michael Ferguson</maintainer>

<license>BSD</license>
<url type="website">https://index.ros.org/p/image_view/github-ros-perception-image_pipeline/</url>
Expand Down
1 change: 1 addition & 0 deletions stereo_image_proc/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<maintainer email="[email protected]">Vincent Rabaud</maintainer>
<maintainer email="[email protected]">Joshua Whitley</maintainer>
<maintainer email="[email protected]">Jacob Perron</maintainer>
<maintainer email="[email protected]">Michael Ferguson</maintainer>

<license>BSD</license>
<url type="website">https://index.ros.org/p/stereo_image_proc/github-ros-perception-image_pipeline/</url>
Expand Down
2 changes: 1 addition & 1 deletion stereo_image_proc/src/stereo_image_proc/disparity_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)
// Declare/read parameters
int queue_size = this->declare_parameter("queue_size", 5);
bool approx = this->declare_parameter("approximate_sync", false);
bool approx_sync_epsilon = this->declare_parameter("approximate_sync_tolerance_seconds", 0.0);
double approx_sync_epsilon = this->declare_parameter("approximate_sync_tolerance_seconds", 0.0);
this->declare_parameter("use_system_default_qos", false);

// Synchronize callbacks
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ PointCloudNode::PointCloudNode(const rclcpp::NodeOptions & options)
// Declare/read parameters
int queue_size = this->declare_parameter("queue_size", 5);
bool approx = this->declare_parameter("approximate_sync", false);
bool approx_sync_epsilon = this->declare_parameter("approximate_sync_tolerance_seconds", 0.0);
double approx_sync_epsilon = this->declare_parameter("approximate_sync_tolerance_seconds", 0.0);
this->declare_parameter("use_system_default_qos", false);
rcl_interfaces::msg::ParameterDescriptor descriptor;
// TODO(ivanpauno): Confirm if using point cloud padding in `sensor_msgs::msg::PointCloud2`
Expand Down
2 changes: 1 addition & 1 deletion tracetools_image_pipeline/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,10 @@
LTTng tracing provider wrapper for image_pipeline ROS 2 meta-package.
</description>
<maintainer email="[email protected]">Víctor Mayoral-Vilches</maintainer>
<maintainer email="[email protected]">Michael Ferguson</maintainer>
<license>Apache 2.0</license>
<author email="[email protected]">Víctor Mayoral-Vilches</author>


<buildtool_depend>ament_cmake_ros</buildtool_depend>
<buildtool_depend>pkg-config</buildtool_depend>

Expand Down

0 comments on commit 00f7b88

Please sign in to comment.