Skip to content

Commit

Permalink
Increase the default max_range limit to 10,000 meters
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu committed Sep 18, 2024
1 parent 5bbfe32 commit 900100c
Show file tree
Hide file tree
Showing 8 changed files with 9 additions and 9 deletions.
2 changes: 1 addition & 1 deletion launch/driver.launch
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@

<arg name="min_range" default="0.0"
doc="minimum lidar range to consider (meters)"/>
<arg name="max_range" default="1000.0"
<arg name="max_range" default="10000.0"
doc="maximum lidar range to consider (meters)"/>

<group ns="$(arg ouster_ns)">
Expand Down
2 changes: 1 addition & 1 deletion launch/replay.launch
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@

<arg name="min_range" default="0.0"
doc="minimum lidar range to consider (meters)"/>
<arg name="max_range" default="1000.0"
<arg name="max_range" default="10000.0"
doc="maximum lidar range to consider (meters)"/>

<group ns="$(arg ouster_ns)">
Expand Down
2 changes: 1 addition & 1 deletion launch/replay_pcap.launch
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@

<arg name="min_range" default="0.0"
doc="minimum lidar range to consider (meters)"/>
<arg name="max_range" default="1000.0"
<arg name="max_range" default="10000.0"
doc="maximum lidar range to consider (meters)"/>

<group ns="$(arg ouster_ns)">
Expand Down
2 changes: 1 addition & 1 deletion launch/sensor.launch
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@

<arg name="min_range" default="0.0"
doc="minimum lidar range to consider (meters)"/>
<arg name="max_range" default="1000.0"
<arg name="max_range" default="10000.0"
doc="maximum lidar range to consider (meters)"/>

<group ns="$(arg ouster_ns)">
Expand Down
2 changes: 1 addition & 1 deletion launch/sensor_mtp.launch
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@

<arg name="min_range" default="0.0"
doc="minimum lidar range to consider (meters)"/>
<arg name="max_range" default="1000.0"
<arg name="max_range" default="10000.0"
doc="maximum lidar range to consider (meters)"/>

<group ns="$(arg ouster_ns)">
Expand Down
2 changes: 1 addition & 1 deletion src/os_cloud_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ class OusterCloud : public nodelet::Nodelet {
auto organized = pnh.param("organized", true);
auto destagger = pnh.param("destagger", true);
auto min_range_m = pnh.param("min_range", 0.0);
auto max_range_m = pnh.param("max_range", 1000.0); // 1000m
auto max_range_m = pnh.param("max_range", 10000.0);
if (min_range_m < 0.0 || max_range_m < 0.0) {
NODELET_FATAL("min_range and max_range need to be positive");
throw std::runtime_error("negative range limits!");
Expand Down
2 changes: 1 addition & 1 deletion src/os_driver_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ class OusterDriver : public OusterSensor {
auto organized = pnh.param("organized", true);
auto destagger = pnh.param("destagger", true);
auto min_range_m = pnh.param("min_range", 0.0);
auto max_range_m = pnh.param("max_range", 1000.0); // 1000m
auto max_range_m = pnh.param("max_range", 10000.0);
if (min_range_m < 0.0 || max_range_m < 0.0) {
NODELET_FATAL("min_range and max_range need to be positive");
throw std::runtime_error("negative range limits!");
Expand Down
4 changes: 2 additions & 2 deletions src/os_sensor_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -566,7 +566,7 @@ void OusterSensor::handle_poll_client_error() {
// in case error continues for a while attempt to recover by
// performing sensor reset
if (++poll_client_error_count > max_poll_client_error_count) {
NODELET_ERROR_STREAM(
NODELET_ERROR(
"maximum number of allowed errors from "
"sensor::poll_client() reached, performing self reset...");
poll_client_error_count = 0;
Expand Down Expand Up @@ -601,7 +601,7 @@ void OusterSensor::handle_imu_packet(sensor::client& cli,
on_imu_packet_msg(imu_packet);
} else {
if (++read_imu_packet_errors > max_read_imu_packet_errors) {
NODELET_ERROR_STREAM(
NODELET_ERROR(
"maximum number of allowed errors from "
"sensor::read_imu_packet() reached, reactivating...");
read_imu_packet_errors = 0;
Expand Down

0 comments on commit 900100c

Please sign in to comment.