Skip to content

Commit

Permalink
Add thread_safe_ring_buffer +
Browse files Browse the repository at this point in the history
Switch to using threads for packet processing in os_sensor node +
Add new wreset service +
Add metadata service to os_replay
  • Loading branch information
Samahu committed Jul 18, 2023
1 parent 628af71 commit e2906d0
Show file tree
Hide file tree
Showing 6 changed files with 592 additions and 178 deletions.
8 changes: 4 additions & 4 deletions include/ouster_ros/os_sensor_nodelet_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,18 +20,18 @@ class OusterSensorNodeletBase : public nodelet::Nodelet {
return arg.find_first_not_of(' ') != std::string::npos;
}

void create_get_metadata_service(ros::NodeHandle& nh);
void create_get_metadata_service();

void create_metadata_publisher(ros::NodeHandle& nh);
void create_metadata_publisher();

void publish_metadata();

void display_lidar_info(const ouster::sensor::sensor_info& info);

std::string read_text_file(const std::string& text_file);

bool write_text_to_file(
const std::string& file_path, const std::string& text);
bool write_text_to_file(const std::string& file_path,
const std::string& text);

protected:
ouster::sensor::sensor_info info;
Expand Down
8 changes: 4 additions & 4 deletions src/os_replay_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,16 +20,16 @@ namespace nodelets_os {
class OusterReplay : public OusterSensorNodeletBase {
private:
virtual void onInit() override {
NODELET_INFO("Running in replay mode");
auto meta_file = get_meta_file();
create_metadata_publisher(getNodeHandle());
create_metadata_publisher();
load_metadata_from_file(meta_file);
publish_metadata();
create_get_metadata_service();
NODELET_INFO("Running in replay mode");
}

std::string get_meta_file() const {
auto& pnh = getPrivateNodeHandle();
auto meta_file = pnh.param("metadata", std::string{});
auto meta_file = getPrivateNodeHandle().param("metadata", std::string{});
if (!is_arg_set(meta_file)) {
NODELET_ERROR("Must specify metadata file in replay mode");
throw std::runtime_error("metadata no specificed");
Expand Down
Loading

0 comments on commit e2906d0

Please sign in to comment.