Skip to content

Commit 7983150

Browse files
Fix upstream API
1 parent 22485ea commit 7983150

File tree

1 file changed

+5
-6
lines changed

1 file changed

+5
-6
lines changed

picknik_reset_fault_controller/src/picknik_reset_fault_controller.cpp

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -62,11 +62,10 @@ CallbackReturn PicknikResetFaultController::on_init() { return CallbackReturn::S
6262
controller_interface::return_type PicknikResetFaultController::update(
6363
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
6464
{
65-
if (realtime_publisher_ && realtime_publisher_->trylock())
65+
if (realtime_publisher_)
6666
{
67-
state_.data = static_cast<bool>(state_interfaces_[StateInterfaces::IN_FAULT].get_value());
68-
realtime_publisher_->msg_.data = state_.data;
69-
realtime_publisher_->unlockAndPublish();
67+
state_.data = static_cast<bool>(state_interfaces_[StateInterfaces::IN_FAULT].get_optional().value());
68+
realtime_publisher_->try_publish(state_);
7069
}
7170

7271
return controller_interface::return_type::OK;
@@ -121,14 +120,14 @@ bool PicknikResetFaultController::resetFault(
121120

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

124-
while (command_interfaces_[CommandInterfaces::RESET_FAULT_ASYNC_SUCCESS].get_value() ==
123+
while (command_interfaces_[CommandInterfaces::RESET_FAULT_ASYNC_SUCCESS].get_optional().value() ==
125124
ASYNC_WAITING)
126125
{
127126
// Asynchronous wait until the hardware interface has set the io value
128127
std::this_thread::sleep_for(std::chrono::milliseconds(50));
129128
}
130129
resp->success = static_cast<bool>(
131-
command_interfaces_[CommandInterfaces::RESET_FAULT_ASYNC_SUCCESS].get_value());
130+
command_interfaces_[CommandInterfaces::RESET_FAULT_ASYNC_SUCCESS].get_optional().value());
132131

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

0 commit comments

Comments
 (0)