Skip to content
Merged
Show file tree
Hide file tree
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
10 changes: 5 additions & 5 deletions ackermann_steering_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -74,12 +74,12 @@ if(BUILD_TESTING)
)

add_rostest_with_parameters_gmock(
test_ackermann_steering_controller_preceeding test/test_ackermann_steering_controller_preceeding.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/ackermann_steering_controller_preceeding_params.yaml)
target_include_directories(test_ackermann_steering_controller_preceeding PRIVATE include)
target_link_libraries(test_ackermann_steering_controller_preceeding ackermann_steering_controller)
test_ackermann_steering_controller_preceding test/test_ackermann_steering_controller_preceding.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/ackermann_steering_controller_preceding_params.yaml)
target_include_directories(test_ackermann_steering_controller_preceding PRIVATE include)
target_link_libraries(test_ackermann_steering_controller_preceding ackermann_steering_controller)
ament_target_dependencies(
test_ackermann_steering_controller_preceeding
test_ackermann_steering_controller_preceding
controller_interface
hardware_interface
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -287,13 +287,13 @@ class AckermannSteeringControllerFixture : public ::testing::Test
std::vector<std::string> joint_names_ = {
rear_wheels_names_[0], rear_wheels_names_[1], front_wheels_names_[0], front_wheels_names_[1]};

std::vector<std::string> rear_wheels_preceeding_names_ = {
std::vector<std::string> rear_wheels_preceding_names_ = {
"pid_controller/rear_right_wheel_joint", "pid_controller/rear_left_wheel_joint"};
std::vector<std::string> front_wheels_preceeding_names_ = {
std::vector<std::string> front_wheels_preceding_names_ = {
"pid_controller/front_right_steering_joint", "pid_controller/front_left_steering_joint"};
std::vector<std::string> preceeding_joint_names_ = {
rear_wheels_preceeding_names_[0], rear_wheels_preceeding_names_[1],
front_wheels_preceeding_names_[0], front_wheels_preceeding_names_[1]};
std::vector<std::string> preceding_joint_names_ = {
rear_wheels_preceding_names_[0], rear_wheels_preceding_names_[1],
front_wheels_preceding_names_[0], front_wheels_preceding_names_[1]};

double wheelbase_ = 3.24644;
double front_wheel_track_ = 2.12321;
Expand All @@ -307,7 +307,7 @@ class AckermannSteeringControllerFixture : public ::testing::Test
std::string steering_interface_name_ = "position";
// defined in setup
std::string traction_interface_name_ = "";
std::string preceeding_prefix_ = "pid_controller";
std::string preceding_prefix_ = "pid_controller";

std::vector<hardware_interface::StateInterface> state_itfs_;
std::vector<hardware_interface::CommandInterface> command_itfs_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,10 @@ TEST_F(AckermannSteeringControllerTest, all_parameters_set_configure_success)

ASSERT_THAT(
controller_->params_.rear_wheels_names,
testing::ElementsAreArray(rear_wheels_preceeding_names_));
testing::ElementsAreArray(rear_wheels_preceding_names_));
ASSERT_THAT(
controller_->params_.front_wheels_names,
testing::ElementsAreArray(front_wheels_preceeding_names_));
testing::ElementsAreArray(front_wheels_preceding_names_));
ASSERT_EQ(controller_->params_.front_steering, front_steering_);
ASSERT_EQ(controller_->params_.open_loop, open_loop_);
ASSERT_EQ(controller_->params_.velocity_rolling_window_size, velocity_rolling_window_size_);
Expand All @@ -57,16 +57,16 @@ TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
EXPECT_EQ(
cmd_if_conf.names[CMD_TRACTION_RIGHT_WHEEL],
preceeding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
preceding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
EXPECT_EQ(
cmd_if_conf.names[CMD_TRACTION_LEFT_WHEEL],
preceeding_prefix_ + "/" + rear_wheels_names_[1] + "/" + traction_interface_name_);
preceding_prefix_ + "/" + rear_wheels_names_[1] + "/" + traction_interface_name_);
EXPECT_EQ(
cmd_if_conf.names[CMD_STEER_RIGHT_WHEEL],
preceeding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
preceding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(
cmd_if_conf.names[CMD_STEER_LEFT_WHEEL],
preceeding_prefix_ + "/" + front_wheels_names_[1] + "/" + steering_interface_name_);
preceding_prefix_ + "/" + front_wheels_names_[1] + "/" + steering_interface_name_);
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

auto state_if_conf = controller_->state_interface_configuration();
Expand Down
10 changes: 5 additions & 5 deletions bicycle_steering_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -72,12 +72,12 @@ if(BUILD_TESTING)
)

add_rostest_with_parameters_gmock(
test_bicycle_steering_controller_preceeding test/test_bicycle_steering_controller_preceeding.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/bicycle_steering_controller_preceeding_params.yaml)
target_include_directories(test_bicycle_steering_controller_preceeding PRIVATE include)
target_link_libraries(test_bicycle_steering_controller_preceeding bicycle_steering_controller)
test_bicycle_steering_controller_preceding test/test_bicycle_steering_controller_preceding.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/bicycle_steering_controller_preceding_params.yaml)
target_include_directories(test_bicycle_steering_controller_preceding PRIVATE include)
target_link_libraries(test_bicycle_steering_controller_preceding bicycle_steering_controller)
ament_target_dependencies(
test_bicycle_steering_controller_preceeding
test_bicycle_steering_controller_preceding
controller_interface
hardware_interface
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -257,11 +257,10 @@ class BicycleSteeringControllerFixture : public ::testing::Test
std::vector<std::string> front_wheels_names_ = {{"steering_axis_joint"}};
std::vector<std::string> joint_names_ = {{rear_wheels_names_[0], front_wheels_names_[0]}};

std::vector<std::string> rear_wheels_preceeding_names_ = {{"pid_controller/rear_wheel_joint"}};
std::vector<std::string> front_wheels_preceeding_names_ = {
{"pid_controller/steering_axis_joint"}};
std::vector<std::string> preceeding_joint_names_ = {
rear_wheels_preceeding_names_[0], front_wheels_preceeding_names_[0]};
std::vector<std::string> rear_wheels_preceding_names_ = {{"pid_controller/rear_wheel_joint"}};
std::vector<std::string> front_wheels_preceding_names_ = {{"pid_controller/steering_axis_joint"}};
std::vector<std::string> preceding_joint_names_ = {
rear_wheels_preceding_names_[0], front_wheels_preceding_names_[0]};

double wheelbase_ = 3.24644;
double front_wheels_radius_ = 0.45;
Expand All @@ -274,7 +273,7 @@ class BicycleSteeringControllerFixture : public ::testing::Test

// defined in setup
std::string traction_interface_name_ = "";
std::string preceeding_prefix_ = "pid_controller";
std::string preceding_prefix_ = "pid_controller";

std::vector<hardware_interface::StateInterface> state_itfs_;
std::vector<hardware_interface::CommandInterface> command_itfs_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,10 @@ TEST_F(BicycleSteeringControllerTest, all_parameters_set_configure_success)

ASSERT_THAT(
controller_->params_.rear_wheels_names,
testing::ElementsAreArray(rear_wheels_preceeding_names_));
testing::ElementsAreArray(rear_wheels_preceding_names_));
ASSERT_THAT(
controller_->params_.front_wheels_names,
testing::ElementsAreArray(front_wheels_preceeding_names_));
testing::ElementsAreArray(front_wheels_preceding_names_));
ASSERT_EQ(controller_->params_.front_steering, front_steering_);
ASSERT_EQ(controller_->params_.open_loop, open_loop_);
ASSERT_EQ(controller_->params_.velocity_rolling_window_size, velocity_rolling_window_size_);
Expand All @@ -55,10 +55,10 @@ TEST_F(BicycleSteeringControllerTest, check_exported_interfaces)
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
EXPECT_EQ(
cmd_if_conf.names[CMD_TRACTION_WHEEL],
preceeding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
preceding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
EXPECT_EQ(
cmd_if_conf.names[CMD_STEER_WHEEL],
preceeding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
preceding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

auto state_if_conf = controller_->state_interface_configuration();
Expand Down
10 changes: 5 additions & 5 deletions mecanum_drive_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -75,12 +75,12 @@ if(BUILD_TESTING)
)

add_rostest_with_parameters_gmock(
test_mecanum_drive_controller_preceeding test/test_mecanum_drive_controller_preceeding.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/mecanum_drive_controller_preceeding_params.yaml)
target_include_directories(test_mecanum_drive_controller_preceeding PRIVATE include)
target_link_libraries(test_mecanum_drive_controller_preceeding mecanum_drive_controller)
test_mecanum_drive_controller_preceding test/test_mecanum_drive_controller_preceding.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/mecanum_drive_controller_preceding_params.yaml)
target_include_directories(test_mecanum_drive_controller_preceding PRIVATE include)
target_link_libraries(test_mecanum_drive_controller_preceding mecanum_drive_controller)
ament_target_dependencies(
test_mecanum_drive_controller_preceeding
test_mecanum_drive_controller_preceding
controller_interface
hardware_interface
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -308,13 +308,13 @@ class SteeringControllersLibraryFixture : public ::testing::Test
std::vector<std::string> joint_names_ = {
rear_wheels_names_[0], rear_wheels_names_[1], front_wheels_names_[0], front_wheels_names_[1]};

std::vector<std::string> rear_wheels_preceeding_names_ = {
std::vector<std::string> rear_wheels_preceding_names_ = {
"pid_controller/rear_right_wheel_joint", "pid_controller/rear_left_wheel_joint"};
std::vector<std::string> front_wheels_preceeding_names_ = {
std::vector<std::string> front_wheels_preceding_names_ = {
"pid_controller/front_right_steering_joint", "pid_controller/front_left_steering_joint"};
std::vector<std::string> preceeding_joint_names_ = {
rear_wheels_preceeding_names_[0], rear_wheels_preceeding_names_[1],
front_wheels_preceeding_names_[0], front_wheels_preceeding_names_[1]};
std::vector<std::string> preceding_joint_names_ = {
rear_wheels_preceding_names_[0], rear_wheels_preceding_names_[1],
front_wheels_preceding_names_[0], front_wheels_preceding_names_[1]};

double wheelbase_ = 3.24644;
double front_wheel_track_ = 2.12321;
Expand All @@ -329,7 +329,7 @@ class SteeringControllersLibraryFixture : public ::testing::Test
std::string steering_interface_name_ = "position";
// defined in setup
std::string traction_interface_name_ = "";
std::string preceeding_prefix_ = "pid_controller";
std::string preceding_prefix_ = "pid_controller";

std::vector<hardware_interface::StateInterface> state_itfs_;
std::vector<hardware_interface::CommandInterface> command_itfs_;
Expand Down
10 changes: 5 additions & 5 deletions tricycle_steering_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -72,12 +72,12 @@ if(BUILD_TESTING)
)

add_rostest_with_parameters_gmock(
test_tricycle_steering_controller_preceeding test/test_tricycle_steering_controller_preceeding.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/tricycle_steering_controller_preceeding_params.yaml)
target_include_directories(test_tricycle_steering_controller_preceeding PRIVATE include)
target_link_libraries(test_tricycle_steering_controller_preceeding tricycle_steering_controller)
test_tricycle_steering_controller_preceding test/test_tricycle_steering_controller_preceding.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/tricycle_steering_controller_preceding_params.yaml)
target_include_directories(test_tricycle_steering_controller_preceding PRIVATE include)
target_link_libraries(test_tricycle_steering_controller_preceding tricycle_steering_controller)
ament_target_dependencies(
test_tricycle_steering_controller_preceeding
test_tricycle_steering_controller_preceding
controller_interface
hardware_interface
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -271,12 +271,12 @@ class TricycleSteeringControllerFixture : public ::testing::Test
std::vector<std::string> joint_names_{
rear_wheels_names_[0], rear_wheels_names_[1], front_wheels_names_[0]};

std::vector<std::string> rear_wheels_preceeding_names_{
std::vector<std::string> rear_wheels_preceding_names_{
"pid_controller/rear_right_wheel_joint", "pid_controller/rear_left_wheel_joint"};
std::vector<std::string> front_wheels_preceeding_names_{"pid_controller/steering_axis_joint"};
std::vector<std::string> preceeding_joint_names_{
rear_wheels_preceeding_names_[0], rear_wheels_preceeding_names_[1],
front_wheels_preceeding_names_[0]};
std::vector<std::string> front_wheels_preceding_names_{"pid_controller/steering_axis_joint"};
std::vector<std::string> preceding_joint_names_{
rear_wheels_preceding_names_[0], rear_wheels_preceding_names_[1],
front_wheels_preceding_names_[0]};

double wheelbase_ = 3.24644;
double wheel_track_ = 1.212121;
Expand All @@ -290,7 +290,7 @@ class TricycleSteeringControllerFixture : public ::testing::Test
std::string steering_interface_name_ = "position";
// defined in setup
std::string traction_interface_name_ = "";
std::string preceeding_prefix_ = "pid_controller";
std::string preceding_prefix_ = "pid_controller";

std::vector<hardware_interface::StateInterface> state_itfs_;
std::vector<hardware_interface::CommandInterface> command_itfs_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,10 @@ TEST_F(TricycleSteeringControllerTest, all_parameters_set_configure_success)

ASSERT_THAT(
controller_->params_.rear_wheels_names,
testing::ElementsAreArray(rear_wheels_preceeding_names_));
testing::ElementsAreArray(rear_wheels_preceding_names_));
ASSERT_THAT(
controller_->params_.front_wheels_names,
testing::ElementsAreArray(front_wheels_preceeding_names_));
testing::ElementsAreArray(front_wheels_preceding_names_));
ASSERT_EQ(controller_->params_.front_steering, front_steering_);
ASSERT_EQ(controller_->params_.open_loop, open_loop_);
ASSERT_EQ(controller_->params_.velocity_rolling_window_size, velocity_rolling_window_size_);
Expand All @@ -55,13 +55,13 @@ TEST_F(TricycleSteeringControllerTest, check_exported_interfaces)
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
EXPECT_EQ(
cmd_if_conf.names[CMD_TRACTION_RIGHT_WHEEL],
preceeding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
preceding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
EXPECT_EQ(
cmd_if_conf.names[CMD_TRACTION_LEFT_WHEEL],
preceeding_prefix_ + "/" + rear_wheels_names_[1] + "/" + traction_interface_name_);
preceding_prefix_ + "/" + rear_wheels_names_[1] + "/" + traction_interface_name_);
EXPECT_EQ(
cmd_if_conf.names[CMD_STEER_WHEEL],
preceeding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
preceding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

auto state_if_conf = controller_->state_interface_configuration();
Expand Down
Loading