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

Infrom user why rt policy could not be set, infrom if is set. (backport #1705) #1709

Merged
merged 2 commits into from
Aug 22, 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
12 changes: 10 additions & 2 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <errno.h>
#include <algorithm>
#include <chrono>
#include <memory>
Expand Down Expand Up @@ -52,12 +53,19 @@ int main(int argc, char ** argv)
{
if (!realtime_tools::configure_sched_fifo(kSchedPriority))
{
RCLCPP_WARN(cm->get_logger(), "Could not enable FIFO RT scheduling policy");
RCLCPP_WARN(
cm->get_logger(),
"Could not enable FIFO RT scheduling policy: with error number <%i>(%s). See "
"[https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] "
"for details on how to enable realtime scheduling.",
errno, strerror(errno));
}
}
else
{
RCLCPP_INFO(cm->get_logger(), "RT kernel is recommended for better performance");
RCLCPP_INFO(
cm->get_logger(), "Successful set up FIFO RT scheduling policy with priority %i.",
kSchedPriority);
}

// for calculating sleep time
Expand Down
Loading