Skip to content

Commit

Permalink
Merge branch 'master' into allow-prepare-comand-mode-switch-only-for-…
Browse files Browse the repository at this point in the history
…existing-and-available-interfaces
  • Loading branch information
destogl authored Jan 3, 2024
2 parents 0a6b107 + e149646 commit 3275d39
Show file tree
Hide file tree
Showing 14 changed files with 134 additions and 111 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci-coverage-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ jobs:
file: ros_ws/lcov/total_coverage.info
flags: unittests
name: codecov-umbrella
- uses: actions/upload-artifact@v3.1.3
- uses: actions/upload-artifact@v4.0.0
with:
name: colcon-logs-ubuntu-22.04-coverage-rolling
path: ros_ws/log
3 changes: 2 additions & 1 deletion .github/workflows/reusable-ros-tooling-source-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ jobs:
with:
target-ros2-distro: ${{ inputs.ros_distro }}
# build all packages listed in the meta package
ref: ${{ inputs.ref }} # otherwise the default branch is used for scheduled workflows
package-name:
controller_interface
controller_manager
Expand All @@ -49,7 +50,7 @@ jobs:
https://raw.githubusercontent.com/ros2/ros2/${{ inputs.ros2_repo_branch }}/ros2.repos
https://raw.githubusercontent.com/${{ github.repository }}/${{ github.sha }}/ros2_control.${{ inputs.ros_distro }}.repos?token=${{ secrets.GITHUB_TOKEN }}
colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml
- uses: actions/upload-artifact@v3.1.3
- uses: actions/upload-artifact@v4.0.0
with:
name: colcon-logs-ubuntu-22.04
path: ros_ws/log
1 change: 1 addition & 0 deletions .github/workflows/reviewer_lottery.yml
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ on:
jobs:
test:
runs-on: ubuntu-latest
if: github.actor != 'dependabot[bot]' && github.actor != 'mergify[bot]'
steps:
- uses: actions/checkout@v4
- uses: uesteibar/reviewer-lottery@v3
Expand Down
6 changes: 3 additions & 3 deletions controller_manager/controller_manager/launch_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,12 +32,12 @@ def generate_load_controller_launch_description(
Examples # noqa: D416
--------
# Assuming the controller type and controller parameters are known to the controller_manager
generate_load_controller_launch_description('joint_state_controller')
generate_load_controller_launch_description('joint_state_broadcaster')
# Passing controller type and controller parameter file to load
generate_load_controller_launch_description(
'joint_state_controller',
controller_type='joint_state_controller/JointStateController',
'joint_state_broadcaster',
controller_type='joint_state_broadcaster/JointStateBroadcaster',
controller_params_file=os.path.join(get_package_share_directory('my_pkg'),
'config', 'controller_params.yaml')
)
Expand Down
15 changes: 12 additions & 3 deletions controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,9 @@ Determinism
-----------

For best performance when controlling hardware you want the controller manager to have as little jitter as possible in the main control loop.
The normal linux kernel is optimized for computational throughput and therefore is not well suited for hardware control.
The two easiest kernel options are the `Real-time Ubuntu 22.04 LTS Beta <https://ubuntu.com/blog/real-time-ubuntu-released>`_ or `linux-image-rt-amd64 <https://packages.debian.org/bullseye/linux-image-rt-amd64>`_ on Debian Bullseye.

If you have a realtime kernel installed, the main thread of Controller Manager attempts to configure ``SCHED_FIFO`` with a priority of ``50``.
Independent of the kernel installed, the main thread of Controller Manager attempts to
configure ``SCHED_FIFO`` with a priority of ``50``.
By default, the user does not have permission to set such a high priority.
To give the user such permissions, add a group named realtime and add the user controlling your robot to this group:

Expand All @@ -36,6 +35,16 @@ Afterwards, add the following limits to the realtime group in ``/etc/security/li
The limits will be applied after you log out and in again.

The normal linux kernel is optimized for computational throughput and therefore is not well suited for hardware control.
Alternatives to the standard kernel include

- `Real-time Ubuntu 22.04 LTS Beta <https://ubuntu.com/blog/real-time-ubuntu-released>`_ on Ubuntu 22.04
- `linux-image-rt-amd64 <https://packages.debian.org/bullseye/linux-image-rt-amd64>`_ on Debian Bullseye
- lowlatency kernel (``sudo apt install linux-lowlatency``) on any ubuntu

Though installing a realtime-kernel will definitely get the best results when it comes to low
jitter, using a lowlatency kernel can improve things a lot with being really easy to install.

Parameters
-----------

Expand Down
2 changes: 1 addition & 1 deletion controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -948,7 +948,7 @@ controller_interface::return_type ControllerManager::switch_controller(
{
RCLCPP_WARN(
get_logger(),
"Controller with name '%s' is not inactive so its following"
"Controller with name '%s' is not inactive so its following "
"controllers do not have to be checked, because it cannot be activated.",
controller_it->info.name.c_str());
status = controller_interface::return_type::ERROR;
Expand Down
16 changes: 7 additions & 9 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,16 +48,14 @@ int main(int argc, char ** argv)
std::thread cm_thread(
[cm]()
{
if (realtime_tools::has_realtime_kernel())
if (!realtime_tools::configure_sched_fifo(kSchedPriority))
{
if (!realtime_tools::configure_sched_fifo(kSchedPriority))
{
RCLCPP_WARN(cm->get_logger(), "Could not enable FIFO RT scheduling policy");
}
}
else
{
RCLCPP_INFO(cm->get_logger(), "RT kernel is recommended for better performance");
RCLCPP_WARN(
cm->get_logger(),
"Could not enable FIFO RT scheduling policy. Consider setting up your user to do FIFO RT "
"scheduling. See "
"[https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] "
"for details.");
}

// for calculating sleep time
Expand Down
2 changes: 1 addition & 1 deletion ros2controlcli/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ Example output:
$ ros2 control list_controller_types
diff_drive_controller/DiffDriveController controller_interface::ControllerInterface
joint_state_controller/JointStateController controller_interface::ControllerInterface
joint_state_broadcaster/JointStateBroadcaster controller_interface::ControllerInterface
joint_trajectory_controller/JointTrajectoryController controller_interface::ControllerInterface
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,12 @@
#include "transmission_interface/differential_transmission_loader.hpp"
#include "transmission_interface/transmission_loader.hpp"

using testing::DoubleNear;
using testing::SizeIs;

// Floating-point value comparison threshold
const double EPS = 1e-5;

class TransmissionPluginLoader
{
public:
Expand Down Expand Up @@ -113,16 +117,16 @@ TEST(DifferentialTransmissionLoaderTest, FullSpec)

const std::vector<double> & actuator_reduction =
differential_transmission->get_actuator_reduction();
EXPECT_EQ(50.0, actuator_reduction[0]);
EXPECT_EQ(-50.0, actuator_reduction[1]);
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
EXPECT_EQ(2.0, joint_reduction[0]);
EXPECT_EQ(-2.0, joint_reduction[1]);
EXPECT_THAT(2.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(-2.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
EXPECT_EQ(0.5, joint_offset[0]);
EXPECT_EQ(-0.5, joint_offset[1]);
EXPECT_THAT(0.5, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(-0.5, DoubleNear(joint_offset[1], EPS));
}

TEST(DifferentialTransmissionLoaderTest, only_mech_red_specified)
Expand Down Expand Up @@ -184,16 +188,16 @@ TEST(DifferentialTransmissionLoaderTest, only_mech_red_specified)

const std::vector<double> & actuator_reduction =
differential_transmission->get_actuator_reduction();
EXPECT_EQ(50.0, actuator_reduction[0]);
EXPECT_EQ(-50.0, actuator_reduction[1]);
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
EXPECT_EQ(1.0, joint_reduction[0]);
EXPECT_EQ(1.0, joint_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(SimpleTransmissionLoaderTest, offset_and_mech_red_not_specified)
Expand Down Expand Up @@ -247,16 +251,16 @@ TEST(SimpleTransmissionLoaderTest, offset_and_mech_red_not_specified)

const std::vector<double> & actuator_reduction =
differential_transmission->get_actuator_reduction();
EXPECT_EQ(1.0, actuator_reduction[0]);
EXPECT_EQ(1.0, actuator_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
EXPECT_EQ(1.0, joint_reduction[0]);
EXPECT_EQ(1.0, joint_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(DifferentialTransmissionLoaderTest, mechanical_reduction_not_a_number)
Expand Down Expand Up @@ -319,16 +323,16 @@ TEST(DifferentialTransmissionLoaderTest, mechanical_reduction_not_a_number)
// default kicks in for ill-defined values
const std::vector<double> & actuator_reduction =
differential_transmission->get_actuator_reduction();
EXPECT_EQ(1.0, actuator_reduction[0]);
EXPECT_EQ(1.0, actuator_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
EXPECT_EQ(1.0, joint_reduction[0]);
EXPECT_EQ(1.0, joint_reduction[1]);
EXPECT_THAT(1.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(1.0, DoubleNear(joint_reduction[1], EPS));

const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(DifferentialTransmissionLoaderTest, offset_ill_defined)
Expand Down Expand Up @@ -393,17 +397,17 @@ TEST(DifferentialTransmissionLoaderTest, offset_ill_defined)
// default kicks in for ill-defined values
const std::vector<double> & actuator_reduction =
differential_transmission->get_actuator_reduction();
EXPECT_EQ(50.0, actuator_reduction[0]);
EXPECT_EQ(-50.0, actuator_reduction[1]);
EXPECT_THAT(50.0, DoubleNear(actuator_reduction[0], EPS));
EXPECT_THAT(-50.0, DoubleNear(actuator_reduction[1], EPS));

const std::vector<double> & joint_reduction = differential_transmission->get_joint_reduction();
EXPECT_EQ(2.0, joint_reduction[0]);
EXPECT_EQ(-2.0, joint_reduction[1]);
EXPECT_THAT(2.0, DoubleNear(joint_reduction[0], EPS));
EXPECT_THAT(-2.0, DoubleNear(joint_reduction[1], EPS));

// default kicks in for ill-defined values
const std::vector<double> & joint_offset = differential_transmission->get_joint_offset();
EXPECT_EQ(0.0, joint_offset[0]);
EXPECT_EQ(0.0, joint_offset[1]);
EXPECT_THAT(0.0, DoubleNear(joint_offset[0], EPS));
EXPECT_THAT(0.0, DoubleNear(joint_offset[1], EPS));
}

TEST(DifferentialTransmissionLoaderTest, mech_red_invalid_value)
Expand Down
14 changes: 7 additions & 7 deletions transmission_interface/test/differential_transmission_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ using transmission_interface::DifferentialTransmission;
using transmission_interface::Exception;
using transmission_interface::JointHandle;
// Floating-point value comparison threshold
const double EPS = 1e-6;
const double EPS = 1e-5;

TEST(PreconditionsTest, ExceptionThrowing)
{
Expand Down Expand Up @@ -79,12 +79,12 @@ TEST(PreconditionsTest, AccessorValidation)

EXPECT_EQ(2u, trans.num_actuators());
EXPECT_EQ(2u, trans.num_joints());
EXPECT_EQ(2.0, trans.get_actuator_reduction()[0]);
EXPECT_EQ(-2.0, trans.get_actuator_reduction()[1]);
EXPECT_EQ(4.0, trans.get_joint_reduction()[0]);
EXPECT_EQ(-4.0, trans.get_joint_reduction()[1]);
EXPECT_EQ(1.0, trans.get_joint_offset()[0]);
EXPECT_EQ(-1.0, trans.get_joint_offset()[1]);
EXPECT_THAT(2.0, DoubleNear(trans.get_actuator_reduction()[0], EPS));
EXPECT_THAT(-2.0, DoubleNear(trans.get_actuator_reduction()[1], EPS));
EXPECT_THAT(4.0, DoubleNear(trans.get_joint_reduction()[0], EPS));
EXPECT_THAT(-4.0, DoubleNear(trans.get_joint_reduction()[1], EPS));
EXPECT_THAT(1.0, DoubleNear(trans.get_joint_offset()[0], EPS));
EXPECT_THAT(-1.0, DoubleNear(trans.get_joint_offset()[1], EPS));
}

void testConfigureWithBadHandles(std::string interface_name)
Expand Down
Loading

0 comments on commit 3275d39

Please sign in to comment.