Skip to content

Commit

Permalink
Set LIDAR FOV on startup
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu committed Aug 18, 2024
1 parent 993e471 commit a7709c3
Show file tree
Hide file tree
Showing 7 changed files with 48 additions and 5 deletions.
7 changes: 7 additions & 0 deletions launch/driver.launch
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,11 @@
xyzir
}"/>

<arg name="azimuth_window_start" default="0" doc="azimuth window start;
values range [0, 360000] millideggrees"/>
<arg name="azimuth_window_end" default="360000" doc="azimuth window end;
values range [0, 360000] millideggrees"/>

<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
output="screen" required="true" args="manager"/>
Expand Down Expand Up @@ -92,6 +97,8 @@
<param name="~/proc_mask" value="$(arg proc_mask)"/>
<param name="~/scan_ring" value="$(arg scan_ring)"/>
<param name="~/point_type" value="$(arg point_type)"/>
<param name="~/azimuth_window_start" value="$(arg azimuth_window_start)"/>
<param name="~/azimuth_window_end" value="$(arg azimuth_window_end)"/>
</node>
</group>

Expand Down
7 changes: 7 additions & 0 deletions launch/record.launch
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,11 @@
xyzir
}"/>

<arg name="azimuth_window_start" default="0" doc="azimuth window start,
values range [0, 360000] millideggrees"/>
<arg name="azimuth_window_end" default="360000" doc="azimuth window end,
values range [0, 360000] millideggrees"/>

<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
output="screen" required="true" args="manager"/>
Expand All @@ -86,6 +91,8 @@
<param name="~/lidar_mode" type="str" value="$(arg lidar_mode)"/>
<param name="~/timestamp_mode" type="str" value="$(arg timestamp_mode)"/>
<param name="~/metadata" type="str" value="$(arg metadata)"/>
<param name="~/azimuth_window_start" value="$(arg azimuth_window_start)"/>
<param name="~/azimuth_window_end" value="$(arg azimuth_window_end)"/>
</node>
</group>

Expand Down
5 changes: 4 additions & 1 deletion launch/replay.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@

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

<remap from="/os_node/imu_packets" to="/ouster/imu_packets"/>
<remap from="/os_node/lidar_packets" to="/ouster/lidar_packets"/>

<arg name="ouster_ns" default="ouster" doc="Override the default namespace of all ouster nodes"/>
<arg name="metadata" default="" doc="path to read metadata file when replaying sensor data"/>
<arg name="bag_file" doc="file name to use for the recorded bag file"/>
Expand Down Expand Up @@ -93,6 +96,6 @@
<node if="$(arg _use_bag_file_name)" pkg="rosbag" type="play" name="rosbag_play_recording"
launch-prefix="bash -c 'sleep 3; $0 $@' "
output="screen" required="true"
args="--clock $(arg bag_file)"/>
args="--clock $(arg bag_file) -l"/>

</launch>
7 changes: 7 additions & 0 deletions launch/sensor.launch
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,11 @@
xyzir
}"/>

<arg name="azimuth_window_start" default="0" doc="azimuth window start;
values range [0, 360000] millideggrees"/>
<arg name="azimuth_window_end" default="360000" doc="azimuth window end;
values range [0, 360000] millideggrees"/>

<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
output="screen" required="true" args="manager"/>
Expand All @@ -90,6 +95,8 @@
<param name="~/lidar_mode" type="str" value="$(arg lidar_mode)"/>
<param name="~/timestamp_mode" type="str" value="$(arg timestamp_mode)"/>
<param name="~/metadata" type="str" value="$(arg metadata)"/>
<param name="~/azimuth_window_start" value="$(arg azimuth_window_start)"/>
<param name="~/azimuth_window_end" value="$(arg azimuth_window_end)"/>
</node>
</group>

Expand Down
7 changes: 7 additions & 0 deletions launch/sensor_mtp.launch
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,11 @@
xyzir
}"/>

<arg name="azimuth_window_start" default="0" doc="azimuth window start,
values range [0, 360000] millideggrees"/>
<arg name="azimuth_window_end" default="360000" doc="azimuth window end,
values range [0, 360000] millideggrees"/>

<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_nodelet_mgr"
output="screen" required="true"
Expand All @@ -97,6 +102,8 @@
<param name="~/lidar_mode" type="str" value="$(arg lidar_mode)"/>
<param name="~/timestamp_mode" type="str" value="$(arg timestamp_mode)"/>
<param name="~/metadata" type="str" value="$(arg metadata)"/>
<param name="~/azimuth_window_start" value="$(arg azimuth_window_start)"/>
<param name="~/azimuth_window_end" value="$(arg azimuth_window_end)"/>
</node>
</group>

Expand Down
17 changes: 15 additions & 2 deletions src/os_sensor_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ using nonstd::optional;

using namespace std::chrono_literals;
using namespace std::string_literals;
using std::to_string;

namespace ouster_ros {

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

if (lidar_port < 0 || lidar_port > 65535) {
auto error_msg =
Expand Down Expand Up @@ -325,6 +329,16 @@ sensor::sensor_config OusterSensor::parse_config_from_ros_parameters() {
}
}

if (azimuth_window_start < MIN_AZW || azimuth_window_start > MAX_AZW ||
azimuth_window_end < MIN_AZW || azimuth_window_end > MAX_AZW) {
auto error_msg = "azimuth window values must be between " +
to_string(MIN_AZW) + " and " + to_string(MAX_AZW);
NODELET_ERROR_STREAM(error_msg);
throw std::runtime_error(error_msg);
}

config.azimuth_window = {azimuth_window_start, azimuth_window_end};

return config;
}

Expand Down Expand Up @@ -450,9 +464,8 @@ void OusterSensor::allocate_buffers() {
bool OusterSensor::init_id_changed(const sensor::packet_format& pf,
const uint8_t* lidar_buf) {
uint32_t current_init_id = pf.init_id(lidar_buf);
if (!last_init_id_initialized) {
if (!last_init_id) {
last_init_id = current_init_id + 1;
last_init_id_initialized = true;
}
if (reset_last_init_id && last_init_id != current_init_id) {
last_init_id = current_init_id;
Expand Down
3 changes: 1 addition & 2 deletions src/os_sensor_nodelet.h
Original file line number Diff line number Diff line change
Expand Up @@ -141,8 +141,7 @@ class OusterSensor : public OusterSensorNodeletBase {
bool force_sensor_reinit = false;
bool reset_last_init_id = true;

bool last_init_id_initialized = false;
uint32_t last_init_id;
nonstd::optional<uint32_t> last_init_id;

// TODO: add as a ros parameter
const int max_poll_client_error_count = 10;
Expand Down

0 comments on commit a7709c3

Please sign in to comment.