Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(config): make parameter 'enabled' dynamic #542

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion velodyne_driver/include/velodyne_driver/driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#ifndef VELODYNE_DRIVER__DRIVER_HPP_
#define VELODYNE_DRIVER__DRIVER_HPP_

#include <atomic>
#include <future>
#include <memory>
#include <string>
Expand Down Expand Up @@ -70,7 +71,7 @@ class VelodyneDriver final : public rclcpp::Node
double rpm; // device rotation rate (RPMs)
int cut_angle; // cutting angle in radians
double time_offset; // time in seconds added to each velodyne time stamp
bool enabled; // polling is enabled
std::atomic<bool> enabled; // polling is enabled
bool timestamp_first_packet; // timestamp based on first packet instead of last one
}
config_;
Expand All @@ -85,6 +86,9 @@ class VelodyneDriver final : public rclcpp::Node
double diag_max_freq_;
std::unique_ptr<diagnostic_updater::TopicDiagnostic> diag_topic_;

std::shared_ptr<rclcpp::ParameterEventHandler> param_subscriber_;
std::shared_ptr<rclcpp::ParameterCallbackHandle> param_enabled_cb_handle_;

// We use this future/promise pair to notify threads that we are shutting down
std::shared_future<void> future_;
std::promise<void> exit_signal_;
Expand Down
8 changes: 6 additions & 2 deletions velodyne_driver/src/driver/driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ VelodyneDriver::VelodyneDriver(const rclcpp::NodeOptions & options)
offset_desc.floating_point_range.push_back(offset_range);
config_.time_offset = this->declare_parameter("time_offset", 0.0, offset_desc);

config_.enabled = this->declare_parameter("enabled", true);
config_.enabled.store(this->declare_parameter("enabled", true));
bool read_once = this->declare_parameter("read_once", false);
bool read_fast = this->declare_parameter("read_fast", false);
double repeat_delay = this->declare_parameter("repeat_delay", 0.0);
Expand All @@ -83,6 +83,10 @@ VelodyneDriver::VelodyneDriver(const rclcpp::NodeOptions & options)
int udp_port = this->declare_parameter("port", static_cast<int>(DATA_PORT_NUMBER));
config_.timestamp_first_packet = this->declare_parameter("timestamp_first_packet", false);

param_subscriber_ = std::make_shared<rclcpp::ParameterEventHandler>(this);
param_enabled_cb_handle_ = param_subscriber_->add_parameter_callback(
"enabled", [this](const rclcpp::Parameter & p) { this->config_.enabled.store(p.as_bool()); });

future_ = exit_signal_.get_future();

// get model name, validate string, determine packet rate
Expand Down Expand Up @@ -196,7 +200,7 @@ VelodyneDriver::~VelodyneDriver()
*/
bool VelodyneDriver::poll()
{
if (!config_.enabled) {
if (!config_.enabled.load()) {
// If we are not enabled exit once a second to let the caller handle
// anything it might need to, such as if it needs to exit.
std::this_thread::sleep_for(std::chrono::seconds(1));
Expand Down
Loading