Skip to content

Commit a7709c3

Browse files
committed
Set LIDAR FOV on startup
1 parent 993e471 commit a7709c3

File tree

7 files changed

+48
-5
lines changed

7 files changed

+48
-5
lines changed

launch/driver.launch

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,11 @@
6565
xyzir
6666
}"/>
6767

68+
<arg name="azimuth_window_start" default="0" doc="azimuth window start;
69+
values range [0, 360000] millideggrees"/>
70+
<arg name="azimuth_window_end" default="360000" doc="azimuth window end;
71+
values range [0, 360000] millideggrees"/>
72+
6873
<group ns="$(arg ouster_ns)">
6974
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
7075
output="screen" required="true" args="manager"/>
@@ -92,6 +97,8 @@
9297
<param name="~/proc_mask" value="$(arg proc_mask)"/>
9398
<param name="~/scan_ring" value="$(arg scan_ring)"/>
9499
<param name="~/point_type" value="$(arg point_type)"/>
100+
<param name="~/azimuth_window_start" value="$(arg azimuth_window_start)"/>
101+
<param name="~/azimuth_window_end" value="$(arg azimuth_window_end)"/>
95102
</node>
96103
</group>
97104

launch/record.launch

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,11 @@
6868
xyzir
6969
}"/>
7070

71+
<arg name="azimuth_window_start" default="0" doc="azimuth window start,
72+
values range [0, 360000] millideggrees"/>
73+
<arg name="azimuth_window_end" default="360000" doc="azimuth window end,
74+
values range [0, 360000] millideggrees"/>
75+
7176
<group ns="$(arg ouster_ns)">
7277
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
7378
output="screen" required="true" args="manager"/>
@@ -86,6 +91,8 @@
8691
<param name="~/lidar_mode" type="str" value="$(arg lidar_mode)"/>
8792
<param name="~/timestamp_mode" type="str" value="$(arg timestamp_mode)"/>
8893
<param name="~/metadata" type="str" value="$(arg metadata)"/>
94+
<param name="~/azimuth_window_start" value="$(arg azimuth_window_start)"/>
95+
<param name="~/azimuth_window_end" value="$(arg azimuth_window_end)"/>
8996
</node>
9097
</group>
9198

launch/replay.launch

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,9 @@
22

33
<param name="use_sim_time" value="true"/>
44

5+
<remap from="/os_node/imu_packets" to="/ouster/imu_packets"/>
6+
<remap from="/os_node/lidar_packets" to="/ouster/lidar_packets"/>
7+
58
<arg name="ouster_ns" default="ouster" doc="Override the default namespace of all ouster nodes"/>
69
<arg name="metadata" default="" doc="path to read metadata file when replaying sensor data"/>
710
<arg name="bag_file" doc="file name to use for the recorded bag file"/>
@@ -93,6 +96,6 @@
9396
<node if="$(arg _use_bag_file_name)" pkg="rosbag" type="play" name="rosbag_play_recording"
9497
launch-prefix="bash -c 'sleep 3; $0 $@' "
9598
output="screen" required="true"
96-
args="--clock $(arg bag_file)"/>
99+
args="--clock $(arg bag_file) -l"/>
97100

98101
</launch>

launch/sensor.launch

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,11 @@
7373
xyzir
7474
}"/>
7575

76+
<arg name="azimuth_window_start" default="0" doc="azimuth window start;
77+
values range [0, 360000] millideggrees"/>
78+
<arg name="azimuth_window_end" default="360000" doc="azimuth window end;
79+
values range [0, 360000] millideggrees"/>
80+
7681
<group ns="$(arg ouster_ns)">
7782
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
7883
output="screen" required="true" args="manager"/>
@@ -90,6 +95,8 @@
9095
<param name="~/lidar_mode" type="str" value="$(arg lidar_mode)"/>
9196
<param name="~/timestamp_mode" type="str" value="$(arg timestamp_mode)"/>
9297
<param name="~/metadata" type="str" value="$(arg metadata)"/>
98+
<param name="~/azimuth_window_start" value="$(arg azimuth_window_start)"/>
99+
<param name="~/azimuth_window_end" value="$(arg azimuth_window_end)"/>
93100
</node>
94101
</group>
95102

launch/sensor_mtp.launch

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -77,6 +77,11 @@
7777
xyzir
7878
}"/>
7979

80+
<arg name="azimuth_window_start" default="0" doc="azimuth window start,
81+
values range [0, 360000] millideggrees"/>
82+
<arg name="azimuth_window_end" default="360000" doc="azimuth window end,
83+
values range [0, 360000] millideggrees"/>
84+
8085
<group ns="$(arg ouster_ns)">
8186
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
8287
output="screen" required="true"
@@ -97,6 +102,8 @@
97102
<param name="~/lidar_mode" type="str" value="$(arg lidar_mode)"/>
98103
<param name="~/timestamp_mode" type="str" value="$(arg timestamp_mode)"/>
99104
<param name="~/metadata" type="str" value="$(arg metadata)"/>
105+
<param name="~/azimuth_window_start" value="$(arg azimuth_window_start)"/>
106+
<param name="~/azimuth_window_end" value="$(arg azimuth_window_end)"/>
100107
</node>
101108
</group>
102109

src/os_sensor_nodelet.cpp

Lines changed: 15 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@ using nonstd::optional;
2525

2626
using namespace std::chrono_literals;
2727
using namespace std::string_literals;
28+
using std::to_string;
2829

2930
namespace ouster_ros {
3031

@@ -232,6 +233,9 @@ sensor::sensor_config OusterSensor::parse_config_from_ros_parameters() {
232233
auto lidar_mode_arg = nh.param("lidar_mode", std::string{});
233234
auto timestamp_mode_arg = nh.param("timestamp_mode", std::string{});
234235
auto udp_profile_lidar_arg = nh.param("udp_profile_lidar", std::string{});
236+
const int MIN_AZW = 0, MAX_AZW = 360000;
237+
auto azimuth_window_start = nh.param("azimuth_window_start", MIN_AZW);
238+
auto azimuth_window_end = nh.param("azimuth_window_end", MAX_AZW);
235239

236240
if (lidar_port < 0 || lidar_port > 65535) {
237241
auto error_msg =
@@ -325,6 +329,16 @@ sensor::sensor_config OusterSensor::parse_config_from_ros_parameters() {
325329
}
326330
}
327331

332+
if (azimuth_window_start < MIN_AZW || azimuth_window_start > MAX_AZW ||
333+
azimuth_window_end < MIN_AZW || azimuth_window_end > MAX_AZW) {
334+
auto error_msg = "azimuth window values must be between " +
335+
to_string(MIN_AZW) + " and " + to_string(MAX_AZW);
336+
NODELET_ERROR_STREAM(error_msg);
337+
throw std::runtime_error(error_msg);
338+
}
339+
340+
config.azimuth_window = {azimuth_window_start, azimuth_window_end};
341+
328342
return config;
329343
}
330344

@@ -450,9 +464,8 @@ void OusterSensor::allocate_buffers() {
450464
bool OusterSensor::init_id_changed(const sensor::packet_format& pf,
451465
const uint8_t* lidar_buf) {
452466
uint32_t current_init_id = pf.init_id(lidar_buf);
453-
if (!last_init_id_initialized) {
467+
if (!last_init_id) {
454468
last_init_id = current_init_id + 1;
455-
last_init_id_initialized = true;
456469
}
457470
if (reset_last_init_id && last_init_id != current_init_id) {
458471
last_init_id = current_init_id;

src/os_sensor_nodelet.h

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -141,8 +141,7 @@ class OusterSensor : public OusterSensorNodeletBase {
141141
bool force_sensor_reinit = false;
142142
bool reset_last_init_id = true;
143143

144-
bool last_init_id_initialized = false;
145-
uint32_t last_init_id;
144+
nonstd::optional<uint32_t> last_init_id;
146145

147146
// TODO: add as a ros parameter
148147
const int max_poll_client_error_count = 10;

0 commit comments

Comments
 (0)