Skip to content

Commit

Permalink
Add a simple test loading limits from parameter file
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 1, 2024
1 parent ffea38a commit 1b69fc9
Show file tree
Hide file tree
Showing 4 changed files with 102 additions and 4 deletions.
5 changes: 5 additions & 0 deletions diff_drive_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,11 @@ if(BUILD_TESTING)
controller_manager
ros2_control_test_assets
)
ament_add_gmock(test_configure_diff_drive_controller test/test_configure_diff_drive_controller.cpp)
ament_target_dependencies(test_configure_diff_drive_controller
controller_manager
ros2_control_test_assets
)
endif()

install(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,18 +25,18 @@ test_diff_drive_controller:

linear.x.max_velocity: .NAN
linear.x.min_velocity: .NAN
linear.x.max_deceleration: .NAN
linear.x.max_acceleration: .NAN
linear.x.max_deceleration_reverse: .NAN
linear.x.max_deceleration: .NAN
linear.x.max_acceleration_reverse: .NAN
linear.x.max_deceleration_reverse: .NAN
linear.x.max_jerk: .NAN
linear.x.min_jerk: .NAN

angular.z.max_velocity: .NAN
angular.z.min_velocity: .NAN
angular.z.max_deceleration: .NAN
angular.z.max_acceleration: .NAN
angular.z.max_deceleration_reverse: .NAN
angular.z.max_deceleration: .NAN
angular.z.max_acceleration_reverse: .NAN
angular.z.max_deceleration_reverse: .NAN
angular.z.max_jerk: .NAN
angular.z.min_jerk: .NAN
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
test_diff_drive_controller:
ros__parameters:
left_wheel_names: ["left_wheels"]
right_wheel_names: ["right_wheels"]

wheel_separation: 0.40
wheel_radius: 0.02

wheel_separation_multiplier: 1.0
left_wheel_radius_multiplier: 1.0
right_wheel_radius_multiplier: 1.0

odom_frame_id: odom
base_frame_id: base_link
pose_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
twist_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

position_feedback: false
open_loop: true
enable_odom_tf: true

cmd_vel_timeout: 0.5 # seconds
publish_limited_velocity: true
velocity_rolling_window_size: 10

linear.x.max_velocity: 10.0
linear.x.min_velocity: -10.0
linear.x.max_acceleration: 10.0
linear.x.max_deceleration: -20.0
linear.x.max_acceleration_reverse: -10.0
linear.x.max_deceleration_reverse: 20.0
linear.x.max_jerk: 50.0
linear.x.min_jerk: -50.0

angular.z.max_velocity: .NAN
angular.z.min_velocity: .NAN
angular.z.max_acceleration: .NAN
angular.z.max_deceleration: .NAN
angular.z.max_acceleration_reverse: .NAN
angular.z.max_deceleration_reverse: .NAN
angular.z.max_jerk: .NAN
angular.z.min_jerk: .NAN
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
// Copyright 2020 PAL Robotics SL.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gmock/gmock.h>
#include <memory>

#include "controller_manager/controller_manager.hpp"
#include "hardware_interface/resource_manager.hpp"
#include "rclcpp/executor.hpp"
#include "rclcpp/executors/single_threaded_executor.hpp"
#include "rclcpp/utilities.hpp"
#include "ros2_control_test_assets/descriptions.hpp"

TEST(TestLoadDiffDriveController, load_configure_controller)
{
std::shared_ptr<rclcpp::Executor> executor =
std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

controller_manager::ControllerManager cm(
executor, ros2_control_test_assets::diffbot_urdf, true, "test_controller_manager");
const std::string test_file_path =
std::string(TEST_FILES_DIRECTORY) + "/config/test_diff_drive_controller_limits.yaml";

cm.set_parameter({"test_diff_drive_controller.params_file", test_file_path});
cm.set_parameter(
{"test_diff_drive_controller.type", "diff_drive_controller/DiffDriveController"});
auto ctr = cm.load_controller("test_diff_drive_controller");
ASSERT_NE(ctr, nullptr);
ASSERT_EQ(
ctr->on_configure(rclcpp_lifecycle::State()), controller_interface::CallbackReturn::SUCCESS);
}

int main(int argc, char ** argv)
{
::testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
int result = RUN_ALL_TESTS();
rclcpp::shutdown();
return result;
}

0 comments on commit 1b69fc9

Please sign in to comment.