Skip to content

Commit

Permalink
Merge branch 'humble' into mergify/bp/humble/pr-742
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Jan 2, 2024
2 parents af8329e + a9ed922 commit 0a3b675
Show file tree
Hide file tree
Showing 10 changed files with 112 additions and 95 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/docker.yml
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ jobs:
type=semver,pattern={{major}}.{{minor}}
- name: Build and push Docker image
uses: docker/build-push-action@v2
uses: docker/build-push-action@v5
with:
context: .
push: true
Expand Down Expand Up @@ -82,7 +82,7 @@ jobs:
type=semver,pattern={{major}}.{{minor}}
- name: Build and push Docker image
uses: docker/build-push-action@v2
uses: docker/build-push-action@v5
with:
context: .
push: true
Expand Down
1 change: 1 addition & 0 deletions .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 Down
3 changes: 2 additions & 1 deletion .github/workflows/reviewer_lottery.yml
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,9 @@ 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@v2
- uses: uesteibar/reviewer-lottery@v3
with:
repo-token: ${{ secrets.GITHUB_TOKEN }}
1 change: 1 addition & 0 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,7 @@ if(BUILD_TESTING)
controller_manager_msgs
ros2_control_test_assets
)
set_tests_properties(test_controller_manager_srvs PROPERTIES TIMEOUT 120)
ament_add_gmock(test_controller_manager_urdf_passing
test/test_controller_manager_urdf_passing.cpp
)
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
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,12 @@
#include "transmission_interface/four_bar_linkage_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,17 +117,17 @@ TEST(FourBarLinkageTransmissionLoaderTest, FullSpec)

const std::vector<double> & actuator_reduction =
four_bar_linkage_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 =
four_bar_linkage_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 = four_bar_linkage_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(FourBarLinkageTransmissionLoaderTest, only_mech_red_specified)
Expand Down Expand Up @@ -185,17 +189,17 @@ TEST(FourBarLinkageTransmissionLoaderTest, only_mech_red_specified)

const std::vector<double> & actuator_reduction =
four_bar_linkage_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 =
four_bar_linkage_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 = four_bar_linkage_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_and_mech_red_not_specified)
Expand Down Expand Up @@ -249,17 +253,17 @@ TEST(DifferentialTransmissionLoaderTest, offset_and_mech_red_not_specified)

const std::vector<double> & actuator_reduction =
four_bar_linkage_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 =
four_bar_linkage_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 = four_bar_linkage_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(FourBarLinkageTransmissionLoaderTest, mechanical_reduction_not_a_number)
Expand Down Expand Up @@ -322,17 +326,17 @@ TEST(FourBarLinkageTransmissionLoaderTest, mechanical_reduction_not_a_number)
// default kicks in for ill-defined values
const std::vector<double> & actuator_reduction =
four_bar_linkage_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 =
four_bar_linkage_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 = four_bar_linkage_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(FourBarLinkageTransmissionLoaderTest, offset_ill_defined)
Expand Down Expand Up @@ -397,18 +401,18 @@ TEST(FourBarLinkageTransmissionLoaderTest, offset_ill_defined)
// default kicks in for ill-defined values
const std::vector<double> & actuator_reduction =
four_bar_linkage_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 =
four_bar_linkage_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 = four_bar_linkage_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(FourBarLinkageTransmissionLoaderTest, mech_red_invalid_value)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ using transmission_interface::FourBarLinkageTransmission;
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 @@ -83,12 +83,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 0a3b675

Please sign in to comment.