fix bug - 前雷达发布
This commit is contained in:
parent
a28814f597
commit
18b2da5450
@ -21,13 +21,13 @@ def generate_launch_description():
|
|||||||
package="rslidar_sdk",
|
package="rslidar_sdk",
|
||||||
executable="rslidar_sdk_node",
|
executable="rslidar_sdk_node",
|
||||||
output="screen",
|
output="screen",
|
||||||
parameters=[{"config_path": config_rear}],
|
parameters=[{"config_path": config_front}],
|
||||||
),
|
|
||||||
Node(
|
|
||||||
namespace="rviz2",
|
|
||||||
package="rviz2",
|
|
||||||
executable="rviz2",
|
|
||||||
arguments=["-d", rviz_config],
|
|
||||||
),
|
),
|
||||||
|
# Node(
|
||||||
|
# namespace="rviz2",
|
||||||
|
# package="rviz2",
|
||||||
|
# executable="rviz2",
|
||||||
|
# arguments=["-d", rviz_config],
|
||||||
|
# ),
|
||||||
]
|
]
|
||||||
)
|
)
|
||||||
|
|||||||
@ -7,7 +7,7 @@ lidar_merger:
|
|||||||
frame_id: "rslidar"
|
frame_id: "rslidar"
|
||||||
queue_size: 3
|
queue_size: 3
|
||||||
time_tolerance: 0.1
|
time_tolerance: 0.1
|
||||||
enable_debug: false
|
enable_debug: true
|
||||||
|
|
||||||
# 点云范围过滤
|
# 点云范围过滤
|
||||||
filter_min_x: -5.0
|
filter_min_x: -5.0
|
||||||
|
|||||||
@ -300,7 +300,7 @@ class LidarMerger : public rclcpp::Node
|
|||||||
last_stats_time_ = now();
|
last_stats_time_ = now();
|
||||||
front_rx_ = rear_rx_ = merged_count_ = front_only_count_ = 0;
|
front_rx_ = rear_rx_ = merged_count_ = front_only_count_ = 0;
|
||||||
|
|
||||||
RCLCPP_INFO(get_logger(), "LidarMerger ready | time_tolerance=%.3fs | use_gpu=%s", time_tolerance_,
|
LOG_INFO("LidarMerger ready | time_tolerance=%.3fs | use_gpu=%s", time_tolerance_,
|
||||||
use_gpu_ ? "true" : "false");
|
use_gpu_ ? "true" : "false");
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -382,7 +382,7 @@ class LidarMerger : public rclcpp::Node
|
|||||||
{
|
{
|
||||||
auto dt = std::chrono::duration_cast<std::chrono::microseconds>(std::chrono::steady_clock::now() - t0)
|
auto dt = std::chrono::duration_cast<std::chrono::microseconds>(std::chrono::steady_clock::now() - t0)
|
||||||
.count();
|
.count();
|
||||||
RCLCPP_DEBUG(get_logger(), "[ch%d] process %.1fms, pts=%zu", channel, dt / 1000.0, pcl_out->size());
|
LOG_DEBUG("[ch%d] process %.1fms, pts=%zu", channel, dt / 1000.0, pcl_out->size());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -487,7 +487,7 @@ class LidarMerger : public rclcpp::Node
|
|||||||
auto dt = std::chrono::duration_cast<std::chrono::microseconds>(std::chrono::steady_clock::now() - t_merge)
|
auto dt = std::chrono::duration_cast<std::chrono::microseconds>(std::chrono::steady_clock::now() - t_merge)
|
||||||
.count();
|
.count();
|
||||||
auto e2e = (now() - front_frame.received_time).seconds();
|
auto e2e = (now() - front_frame.received_time).seconds();
|
||||||
RCLCPP_INFO(get_logger(), "[Merge#%d] timediff=%.3fs, merge=%.1fms, e2e_delay=%.3fs", merged_count_.load(),
|
LOG_INFO("[Merge#%d] timediff=%.3fs, merge=%.1fms, e2e_delay=%.3fs", merged_count_.load(),
|
||||||
min_diff, dt / 1000.0, e2e);
|
min_diff, dt / 1000.0, e2e);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -511,7 +511,7 @@ class LidarMerger : public rclcpp::Node
|
|||||||
|
|
||||||
if (enable_debug_)
|
if (enable_debug_)
|
||||||
{
|
{
|
||||||
RCLCPP_INFO(get_logger(), "[FrontOnly#%d] No match (min_diff=%.3fs), published front radar only",
|
LOG_INFO_THROTTLE(1000,"[FrontOnly#%d] No match (min_diff=%.3fs), published front lidar only",
|
||||||
front_only_count_.load(), min_diff);
|
front_only_count_.load(), min_diff);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -533,7 +533,7 @@ class LidarMerger : public rclcpp::Node
|
|||||||
|
|
||||||
if (enable_debug_)
|
if (enable_debug_)
|
||||||
{
|
{
|
||||||
RCLCPP_INFO(get_logger(), "[FrontOnly#%d] Only front radar available", front_only_count_.load());
|
LOG_INFO_THROTTLE(1000,"[FrontOnly#%d] Only front lidar available", front_only_count_.load());
|
||||||
}
|
}
|
||||||
|
|
||||||
cf.erase(cf.begin());
|
cf.erase(cf.begin());
|
||||||
@ -560,7 +560,7 @@ class LidarMerger : public rclcpp::Node
|
|||||||
}
|
}
|
||||||
catch (const tf2::TransformException& e)
|
catch (const tf2::TransformException& e)
|
||||||
{
|
{
|
||||||
RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 1000, "TF failed: %s", e.what());
|
LOG_WARN_THROTTLE(1000, "TF failed: %s", e.what());
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -850,7 +850,7 @@ class LidarMerger : public rclcpp::Node
|
|||||||
|
|
||||||
if (fc->fields != rc->fields || fc->point_step != rc->point_step || fc->is_bigendian != rc->is_bigendian)
|
if (fc->fields != rc->fields || fc->point_step != rc->point_step || fc->is_bigendian != rc->is_bigendian)
|
||||||
{
|
{
|
||||||
RCLCPP_ERROR(get_logger(), "Cloud format mismatch!");
|
LOG_ERROR("Cloud format mismatch!");
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1100,7 +1100,7 @@ class LidarMerger : public rclcpp::Node
|
|||||||
use_gpu_ = false;
|
use_gpu_ = false;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
RCLCPP_INFO(get_logger(), "[GPU] Initialized, max_voxel_dim=%d", max_voxel_dim);
|
LOG_INFO("[GPU] Initialized, max_voxel_dim=%d", max_voxel_dim);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user