Skip to content

Commit 5275d43

Browse files
authored
Merge pull request #24 from NVIDIA-ISAAC-ROS/release-2.1
Isaac ROS 2.1.0
2 parents 4a96b3d + def4a38 commit 5275d43

File tree

4 files changed

+13
-4
lines changed

4 files changed

+13
-4
lines changed

isaac_ros_occupancy_grid_localizer/config/occupancy_grid_localizer_node.yaml

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -110,6 +110,10 @@ components:
110110
rx_localization_result: rx_localization_result
111111
tx_pose3d_cov: tx_pose3d_cov
112112
allocator: allocator
113+
- type: nvidia::gxf::MemoryAvailableSchedulingTerm
114+
parameters:
115+
allocator: allocator
116+
min_blocks: 1
113117
---
114118
#######################
115119
# Global Localization #
@@ -226,6 +230,10 @@ components:
226230
tx_memory_type: 0
227231
allocator: allocator
228232
cuda_stream: cuda_stream/cuda_stream
233+
- type: nvidia::gxf::MemoryAvailableSchedulingTerm
234+
parameters:
235+
allocator: allocator
236+
min_blocks: 1
229237
---
230238
name: sink
231239
components:

isaac_ros_occupancy_grid_localizer/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
2222
<package format="3">
2323
<name>isaac_ros_occupancy_grid_localizer</name>
24-
<version>2.0.0</version>
24+
<version>2.1.0</version>
2525
<description>Occupancy Grid Global Localizer.</description>
2626

2727
<maintainer email="[email protected]">Ashwin Varghese Kuruttukulam</maintainer>

isaac_ros_pointcloud_utils/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
2222
<package format="3">
2323
<name>isaac_ros_pointcloud_utils</name>
24-
<version>2.0.0</version>
24+
<version>2.1.0</version>
2525
<description>Isaac ROS Point Cloud Utilities.</description>
2626

2727
<maintainer email="[email protected]">Ashwin Varghese Kuruttukulam</maintainer>

isaac_ros_pointcloud_utils/src/pointcloud_to_flatscan_node.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -87,6 +87,7 @@ const nitros::NitrosPublisherSubscriberConfigMap CONFIG_MAP = {
8787
.qos = rclcpp::QoS(10),
8888
.compatible_data_format = OUTPUT_DEFAULT_TENSOR_FORMAT_FLATSCAN,
8989
.topic_name = OUTPUT_TOPIC_NAME_FLATSCAN,
90+
.frame_id_source_key = INPUT_COMPONENT_KEY_POINTCLOUD,
9091
}
9192
}
9293
};
@@ -108,8 +109,8 @@ PointCloudToFlatScanNode::PointCloudToFlatScanNode(const rclcpp::NodeOptions & o
108109
min_z_(declare_parameter<double>("min_z", -0.1)),
109110
max_z_(declare_parameter<double>("max_z", 0.1)),
110111
max_points_(declare_parameter<double>("max_points", 150000)),
111-
threshold_x_axis_(declare_parameter<double>("threshold_x_axis", false)),
112-
threshold_y_axis_(declare_parameter<double>("threshold_y_axis", false))
112+
threshold_x_axis_(declare_parameter<bool>("threshold_x_axis", false)),
113+
threshold_y_axis_(declare_parameter<bool>("threshold_y_axis", false))
113114
{
114115
RCLCPP_DEBUG(get_logger(), "[PointCloudToFlatScanNode] Constructor");
115116

0 commit comments

Comments
 (0)