diff --git a/velodyne_pointcloud/config/VLP16-velodyne_convert_node-params.yaml b/velodyne_pointcloud/config/VLP16-velodyne_convert_node-params.yaml index 598ff493f..af5d3d6d4 100644 --- a/velodyne_pointcloud/config/VLP16-velodyne_convert_node-params.yaml +++ b/velodyne_pointcloud/config/VLP16-velodyne_convert_node-params.yaml @@ -2,6 +2,8 @@ velodyne_convert_node: ros__parameters: calibration: VLP16db.yaml model: VLP16 + target_frame: velodyne + fixed_frame: velodyne min_range: 0.9 max_range: 130.0 view_direction: 0.0 diff --git a/velodyne_pointcloud/config/VLP32C-velodyne_convert_node-params.yaml b/velodyne_pointcloud/config/VLP32C-velodyne_convert_node-params.yaml index fa2ad0fa0..0990fc946 100644 --- a/velodyne_pointcloud/config/VLP32C-velodyne_convert_node-params.yaml +++ b/velodyne_pointcloud/config/VLP32C-velodyne_convert_node-params.yaml @@ -2,6 +2,8 @@ velodyne_convert_node: ros__parameters: calibration: VeloView-VLP-32C.yaml model: 32C + target_frame: velodyne + fixed_frame: velodyne min_range: 0.9 max_range: 200.0 view_direction: 0.0 diff --git a/velodyne_pointcloud/src/conversions/convert.cpp b/velodyne_pointcloud/src/conversions/convert.cpp index d48fbd9e8..43845bb4d 100644 --- a/velodyne_pointcloud/src/conversions/convert.cpp +++ b/velodyne_pointcloud/src/conversions/convert.cpp @@ -100,10 +100,10 @@ Convert::Convert(const rclcpp::NodeOptions & options) view_width_desc.floating_point_range.push_back(view_width_range); double view_width = this->declare_parameter("view_width", 2.0 * M_PI, view_width_desc); - bool organize_cloud = this->declare_parameter("organize_cloud", true); + bool organize_cloud = this->declare_parameter("organize_cloud", false); - std::string target_frame = this->declare_parameter("target_frame", ""); - std::string fixed_frame = this->declare_parameter("fixed_frame", ""); + std::string target_frame = this->declare_parameter("target_frame", "velodyne"); + std::string fixed_frame = this->declare_parameter("fixed_frame", "velodyne"); RCLCPP_INFO(this->get_logger(), "correction angles: %s", calibration_file.c_str());