We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
There was an error while loading. Please reload this page.
1 parent 5707dca commit 738833fCopy full SHA for 738833f
spinnaker_camera_driver/src/camera_driver.cpp
@@ -43,7 +43,7 @@ CameraDriver::CameraDriver(const rclcpp::NodeOptions & options) : NodeType("came
43
get_node_base_interface()->get_context()->add_pre_shutdown_callback(
44
std::bind(&CameraDriver::preShutdown, this));
45
46
- if (declare_parameter("auto_start", true)) {
+ if (declare_parameter<bool>("auto_start", true)) {
47
// defer because one cannot call some of the required methods inside the constructor
48
timer_ = create_wall_timer(std::chrono::microseconds(0), [this]() -> void {
49
timer_->cancel();
0 commit comments