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

Adapt lock_memory API style #1892

Draft
wants to merge 1 commit into
base: master
Choose a base branch
from
Draft
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
9 changes: 6 additions & 3 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,10 +60,13 @@ int main(int argc, char ** argv)
const bool use_sim_time = cm->get_parameter_or("use_sim_time", false);

const bool lock_memory = cm->get_parameter_or<bool>("lock_memory", false);
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());
auto lock_result = realtime_tools::lock_memory();
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
auto lock_result = realtime_tools::lock_memory();
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());
}
}

const int cpu_affinity = cm->get_parameter_or<int>("cpu_affinity", -1);
Expand Down
Loading