Skip to content
Open
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
Original file line number Diff line number Diff line change
Expand Up @@ -62,11 +62,14 @@ CallbackReturn PicknikResetFaultController::on_init() { return CallbackReturn::S
controller_interface::return_type PicknikResetFaultController::update(
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
if (realtime_publisher_ && realtime_publisher_->trylock())
if (realtime_publisher_)
{
state_.data = static_cast<bool>(state_interfaces_[StateInterfaces::IN_FAULT].get_value());
realtime_publisher_->msg_.data = state_.data;
realtime_publisher_->unlockAndPublish();
auto state_op = state_interfaces_[StateInterfaces::IN_FAULT].get_optional();
if (state_op.has_value())
{
state_.data = static_cast<bool>(state_op.value());
}
realtime_publisher_->try_publish(state_);
Copy link
Member

@nbbrooks nbbrooks Dec 7, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

try_publish is available in Jazzy and newer, correct?

In a separate PR we should update the readme and the table of supported versions , branches, build statuses, etc to reflect this.

For this to pass CI I'll need to disable the Humble CI job on main...hmm so maybe I should do that first along with ^

Copy link
Member

@nbbrooks nbbrooks Dec 7, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In general, for ros2_control changes, what is the recommended way to look up what API is available in what version? Of the options I have considered thus far I don't love any of them:

  1. Check the git blame for the function I am migrating to on rolling, navigate to the associated PR, and look for comments/mentioned PRs about backports
  2. Individually check each distro version migration guide (e.g. https://control.ros.org/rolling/doc/ros2_control/doc/migration.html) for mention of the API - find the earlier distro migration guide mentioning it and assume only that and newer distros have it (I think I might be missing backports?)
  3. Go to the main implementation of the function in question and check if it is present in the distro-specific branches (doesn't work if files just got reorganized but the functionality was preserved?)
  4. This just came to mind: Something involving searching the docs.ros.org api for the function in each distro in Q? (e.g. https://docs.ros.org/en/rolling/p/realtime_tools/search.html?q=try_publish&check_keywords=yes&area=default)

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ad 2: When some new API is backported, it might be that there is no hint in the migration notes about that (nothing to migrate because we don't remove/break API). The release notes still should reflect this.

I'd recommend option 4, as it is the quickest one. And add proper CI jobs for all target distros ;)

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nice catch @nbbrooks !

}

return controller_interface::return_type::OK;
Expand Down Expand Up @@ -121,14 +124,23 @@ bool PicknikResetFaultController::resetFault(

RCLCPP_INFO(get_node()->get_logger(), "Trying to reset faults on hardware controller.");

while (command_interfaces_[CommandInterfaces::RESET_FAULT_ASYNC_SUCCESS].get_value() ==
ASYNC_WAITING)
while (command_interfaces_[CommandInterfaces::RESET_FAULT_ASYNC_SUCCESS].get_optional().value_or(
ASYNC_WAITING) == ASYNC_WAITING)
{
// Asynchronous wait until the hardware interface has set the io value
std::this_thread::sleep_for(std::chrono::milliseconds(50));
}
resp->success = static_cast<bool>(
command_interfaces_[CommandInterfaces::RESET_FAULT_ASYNC_SUCCESS].get_value());
auto async_result_op =
command_interfaces_[CommandInterfaces::RESET_FAULT_ASYNC_SUCCESS].get_optional();
if (!async_result_op.has_value())
{
RCLCPP_ERROR(
get_node()->get_logger(),
"Failed to get result of fault reset command from hardware controller.");
resp->success = false;
return resp->success;
}
resp->success = static_cast<bool>(async_result_op.value());

RCLCPP_INFO(
get_node()->get_logger(), "Resetting fault on hardware controller '%s'!",
Expand Down