Skip to content

Commit

Permalink
Update the use explict parameters for the wheels.
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl committed Jun 19, 2024
1 parent 98b1e59 commit a34c665
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 9 deletions.
10 changes: 5 additions & 5 deletions mecanum_drive_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -58,12 +58,12 @@ if(BUILD_TESTING)
find_package(hardware_interface REQUIRED)
find_package(ros2_control_test_assets REQUIRED)

ament_add_gmock(test_load_mecanum_drive_controller test/test_load_mecanum_drive_controller.cpp)
target_include_directories(test_load_mecanum_drive_controller PRIVATE include)
ament_target_dependencies(
test_load_mecanum_drive_controller
add_rostest_with_parameters_gmock(test_load_mecanum_drive_controller
test/test_load_mecanum_drive_controller.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/mecanum_drive_controller_params.yaml
)
ament_target_dependencies(test_load_mecanum_drive_controller
controller_manager
hardware_interface
ros2_control_test_assets
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,8 @@
#include "rclcpp/utilities.hpp"
#include "ros2_control_test_assets/descriptions.hpp"

TEST(TestLoadMecanumDriveController, when_loading_controller_expect_no_exception)
TEST(TestLoadMecanumDriveController, load_controller)
{
rclcpp::init(0, nullptr);

std::shared_ptr<rclcpp::Executor> executor =
std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

Expand All @@ -41,3 +39,12 @@ TEST(TestLoadMecanumDriveController, when_loading_controller_expect_no_exception

rclcpp::shutdown();
}

int main(int argc, char ** argv)
{
::testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
int result = RUN_ALL_TESTS();
rclcpp::shutdown();
return result;
}
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,11 @@ class MecanumDriveControllerFixture : public ::testing::Test
protected:
void SetUpController(const std::string controller_name = "test_mecanum_drive_controller")
{
ASSERT_EQ(controller_->init(controller_name), controller_interface::return_type::OK);
const auto urdf = "";
const auto ns = "";
ASSERT_EQ(
controller_->init(controller_name, urdf, 0, ns, controller_->define_custom_node_options()),
controller_interface::return_type::OK);

std::vector<hardware_interface::LoanedCommandInterface> command_ifs;
command_itfs_.reserve(joint_command_values_.size());
Expand Down

0 comments on commit a34c665

Please sign in to comment.