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

Fix deprecated usage of lock_memory API #1970

Merged
merged 5 commits into from
Dec 23, 2024
Merged
Changes from 3 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
8 changes: 5 additions & 3 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,10 +61,12 @@ int main(int argc, char ** argv)

const bool has_realtime = realtime_tools::has_realtime_kernel();
const bool lock_memory = cm->get_parameter_or<bool>("lock_memory", has_realtime);
std::string message;
if (lock_memory && !realtime_tools::lock_memory(message))
if (lock_memory)
{
RCLCPP_WARN(cm->get_logger(), "Unable to lock the memory : '%s'", message.c_str());
const auto lock_result = realtime_tools::lock_memory();
if (!lock_result.first) {
RCLCPP_WARN(cm->get_logger(), "Unable to lock the memory: '%s'", lock_result.second.c_str());
}
}

rclcpp::Parameter cpu_affinity_param;
Expand Down
Loading