Skip to content

Commit

Permalink
Remap metadata topic + add loop to pcap + add play delay & play rate
Browse files Browse the repository at this point in the history
  • Loading branch information
Samahu committed Oct 28, 2024
1 parent 55519ed commit 0ed1cb8
Show file tree
Hide file tree
Showing 3 changed files with 29 additions and 9 deletions.
11 changes: 8 additions & 3 deletions launch/replay.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,13 @@
<param name="use_sim_time" value="true"/>

<arg name="loop" default="false" doc="request loop playback"/>
<arg name="play_delay" default="0.4"/>
<arg name="play_rate" default="1.0"/>

<arg if="$(arg loop)" name="_loop" value="--loop"/>
<arg unless="$(arg loop)" name="_loop" value=" "/>

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

Expand Down Expand Up @@ -111,9 +115,10 @@

<arg name="_use_bag_file_name" value="$(eval not (bag_file == ''))"/>

<node if="$(arg _use_bag_file_name)" pkg="rosbag" type="play" name="rosbag_play_recording"
launch-prefix="bash -c 'sleep 3; $0 $@' "
<node if="$(arg _use_bag_file_name)" pkg="rosbag" type="play"
name="rosbag_play_recording"
launch-prefix="bash -c 'sleep $(arg play_delay); $0 $@' "
output="screen" required="true"
args="--clock $(arg bag_file) $(arg _loop)"/>
args="--clock $(arg bag_file) $(arg _loop) --rate $(arg play_rate)"/>

</launch>
11 changes: 9 additions & 2 deletions launch/replay_pcap.launch
Original file line number Diff line number Diff line change
@@ -1,8 +1,13 @@
<launch>

<!-- NOTE: pcap replay node does not implement clock-->
<!-- NOTE: pcap replay node does not implement clock -->
<param name="use_sim_time" value="false"/>

<arg name="loop" default="false" doc="request loop playback"/>
<arg name="play_delay" default="0.4" doc="playback start delay"/>
<arg name="progress_update_freq" default="3.0"
doc="progress update frequency per second"/>

<arg name="ouster_ns" default="ouster" doc="Override the default namespace of all ouster nodes"/>
<arg name="metadata" doc="path to read metadata file when replaying sensor data"/>
<arg name="pcap_file" doc="file name to use for the recorded pcap file"/>
Expand Down Expand Up @@ -71,10 +76,12 @@
<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet"
name="os_node" output="screen" required="true"
launch-prefix="bash -c 'sleep 3; $0 $@' "
launch-prefix="bash -c 'sleep $(arg play_delay); $0 $@' "
args="load ouster_ros/OusterPcap os_nodelet_mgr">
<param name="~/metadata" value="$(arg metadata)"/>
<param name="~/pcap_file" value="$(arg pcap_file)"/>
<param name="~/loop" value="$(arg loop)"/>
<param name="~/progress_update_freq" value="$(arg progress_update_freq)"/>
</node>
</group>

Expand Down
16 changes: 12 additions & 4 deletions src/os_pcap_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,10 @@ class OusterPcap : public OusterSensorNodeletBase {
virtual void onInit() override {
auto meta_file = get_meta_file();
auto pcap_file = get_pcap_file();
loop = getPrivateNodeHandle().param("loop", false);
progress_update_freq = getPrivateNodeHandle().param("progress_update_freq", 1.0);
if (progress_update_freq < 0.001)
progress_update_freq = 0.001;
create_metadata_pub();
load_metadata_from_file(meta_file);
allocate_buffers();
Expand Down Expand Up @@ -104,10 +108,12 @@ class OusterPcap : public OusterSensorNodeletBase {
packet_read_active = true;
packet_read_thread = std::make_unique<std::thread>([this]() {
auto& pf = sensor::get_format(info);
while (packet_read_active) {
do {
read_packets(*pcap, pf);
}
pcap->reset();
} while (loop);
NODELET_DEBUG("packet_read_thread done.");
ros::shutdown();
});
}

Expand All @@ -125,9 +131,9 @@ class OusterPcap : public OusterSensorNodeletBase {
auto file_start = packet_info.timestamp;
auto last_update = file_start;
using namespace std::chrono_literals;
const auto UPDATE_PERIOD = duration_cast<microseconds>(1s / 3);
const auto UPDATE_PERIOD = duration_cast<microseconds>(1s / progress_update_freq);

while (ros::ok() && payload_size) {
while (ros::ok() && packet_read_active && payload_size) {
auto start = high_resolution_clock::now();
if (packet_info.dst_port == info.config.udp_port_imu) {
std::memcpy(imu_packet.buf.data(), pcap.current_data(),
Expand Down Expand Up @@ -167,6 +173,8 @@ class OusterPcap : public OusterSensorNodeletBase {
PacketMsg imu_packet;
ros::Publisher lidar_packet_pub;
ros::Publisher imu_packet_pub;
bool loop;
double progress_update_freq;

std::atomic<bool> packet_read_active = {false};
std::unique_ptr<std::thread> packet_read_thread;
Expand Down

0 comments on commit 0ed1cb8

Please sign in to comment.