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

Use post-set parameters callback (backport #41) #42

Merged
merged 1 commit into from
May 8, 2024
Merged
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
25 changes: 14 additions & 11 deletions aruco_opencv/src/aruco_tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ class ArucoTracker : public rclcpp_lifecycle::LifecycleNode

// ROS
OnSetParametersCallbackHandle::SharedPtr on_set_parameter_callback_handle_;
PostSetParametersCallbackHandle::SharedPtr post_set_parameter_callback_handle_;
rclcpp_lifecycle::LifecyclePublisher<aruco_opencv_msgs::msg::ArucoDetection>::SharedPtr
detection_pub_;
rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::Image>::SharedPtr debug_pub_;
Expand Down Expand Up @@ -160,11 +161,10 @@ class ArucoTracker : public rclcpp_lifecycle::LifecycleNode
detection_pub_->on_activate();
debug_pub_->on_activate();

on_set_parameter_callback_handle_ =
add_on_set_parameters_callback(
std::bind(
&ArucoTracker::callback_on_set_parameters,
this, std::placeholders::_1));
on_set_parameter_callback_handle_ = add_on_set_parameters_callback(
std::bind(&ArucoTracker::callback_on_set_parameters, this, std::placeholders::_1));
post_set_parameter_callback_handle_ = add_post_set_parameters_callback(
std::bind(&ArucoTracker::callback_post_set_parameters, this, std::placeholders::_1));

RCLCPP_INFO(get_logger(), "Waiting for first camera info...");

Expand Down Expand Up @@ -204,6 +204,7 @@ class ArucoTracker : public rclcpp_lifecycle::LifecycleNode
RCLCPP_INFO(get_logger(), "Deactivating");

on_set_parameter_callback_handle_.reset();
post_set_parameter_callback_handle_.reset();
cam_info_sub_.reset();
img_sub_.reset();
compressed_img_sub_.reset();
Expand Down Expand Up @@ -235,6 +236,7 @@ class ArucoTracker : public rclcpp_lifecycle::LifecycleNode
RCLCPP_INFO(get_logger(), "Shutting down");

on_set_parameter_callback_handle_.reset();
post_set_parameter_callback_handle_.reset();
cam_info_sub_.reset();
img_sub_.reset();
compressed_img_sub_.reset();
Expand Down Expand Up @@ -328,6 +330,11 @@ class ArucoTracker : public rclcpp_lifecycle::LifecycleNode
}
}

return result;
}

void callback_post_set_parameters(const std::vector<rclcpp::Parameter> & parameters)
{
bool aruco_param_changed = false;
for (auto & param : parameters) {
if (param.get_name() == "marker_size") {
Expand All @@ -345,13 +352,9 @@ class ArucoTracker : public rclcpp_lifecycle::LifecycleNode
"Parameter \"" << param.get_name() << "\" changed to " << param.value_to_string());
}

if (!aruco_param_changed) {
return result;
if (aruco_param_changed) {
retrieve_aruco_parameters(*this, detector_parameters_);
}

retrieve_aruco_parameters(*this, detector_parameters_);

return result;
}

void load_boards()
Expand Down
Loading