Skip to content

Commit

Permalink
Fix merge conflicts
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Mar 13, 2024
1 parent dbe2658 commit eb88798
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 99 deletions.
38 changes: 0 additions & 38 deletions tricycle_controller/src/tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,47 +52,9 @@ CallbackReturn TricycleController::on_init()
{
try
{
<<<<<<< HEAD
// with the lifecycle node being initialized, we can declare parameters
auto_declare<std::string>("traction_joint_name", std::string());
auto_declare<std::string>("steering_joint_name", std::string());

auto_declare<double>("wheelbase", wheel_params_.wheelbase);
auto_declare<double>("wheel_radius", wheel_params_.radius);

auto_declare<std::string>("odom_frame_id", odom_params_.odom_frame_id);
auto_declare<std::string>("base_frame_id", odom_params_.base_frame_id);
auto_declare<std::vector<double>>("pose_covariance_diagonal", std::vector<double>());
auto_declare<std::vector<double>>("twist_covariance_diagonal", std::vector<double>());
auto_declare<bool>("open_loop", odom_params_.open_loop);
auto_declare<bool>("enable_odom_tf", odom_params_.enable_odom_tf);
auto_declare<bool>("odom_only_twist", odom_params_.odom_only_twist);

auto_declare<int>("cmd_vel_timeout", cmd_vel_timeout_.count());
auto_declare<bool>("publish_ackermann_command", publish_ackermann_command_);
auto_declare<int>("velocity_rolling_window_size", 10);
auto_declare<bool>("use_stamped_vel", use_stamped_vel_);

auto_declare<double>("traction.max_velocity", NAN);
auto_declare<double>("traction.min_velocity", NAN);
auto_declare<double>("traction.max_acceleration", NAN);
auto_declare<double>("traction.min_acceleration", NAN);
auto_declare<double>("traction.max_deceleration", NAN);
auto_declare<double>("traction.min_deceleration", NAN);
auto_declare<double>("traction.max_jerk", NAN);
auto_declare<double>("traction.min_jerk", NAN);

auto_declare<double>("steering.max_position", NAN);
auto_declare<double>("steering.min_position", NAN);
auto_declare<double>("steering.max_velocity", NAN);
auto_declare<double>("steering.min_velocity", NAN);
auto_declare<double>("steering.max_acceleration", NAN);
auto_declare<double>("steering.min_acceleration", NAN);
=======
// Create the parameter listener and get the parameters
param_listener_ = std::make_shared<ParamListener>(get_node());
params_ = param_listener_->get_params();
>>>>>>> 8d732f1 ([tricycle_controller] Use generate_parameter_library (#957))
}
catch (const std::exception & e)
{
Expand Down
62 changes: 1 addition & 61 deletions tricycle_controller/test/test_tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,7 @@ class TestTricycleController : public ::testing::Test
parameter_overrides.insert(parameter_overrides.end(), parameters.begin(), parameters.end());
node_options.parameter_overrides(parameter_overrides);

return controller_->init(controller_name, urdf_, 0, "", node_options);
return controller_->init(controller_name, "", node_options);
}

const std::string controller_name = "test_tricycle_controller";
Expand All @@ -195,43 +195,22 @@ class TestTricycleController : public ::testing::Test

TEST_F(TestTricycleController, init_fails_without_parameters)
{
<<<<<<< HEAD
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
=======
const auto ret = controller_->init(controller_name, urdf_, 0);
ASSERT_EQ(ret, controller_interface::return_type::ERROR);
>>>>>>> 8d732f1 ([tricycle_controller] Use generate_parameter_library (#957))
}

TEST_F(TestTricycleController, init_fails_if_only_traction_or_steering_side_defined)
{
<<<<<<< HEAD
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
=======
ASSERT_EQ(
InitController(traction_joint_name, std::string()), controller_interface::return_type::ERROR);
>>>>>>> 8d732f1 ([tricycle_controller] Use generate_parameter_library (#957))

ASSERT_EQ(
InitController(std::string(), steering_joint_name), controller_interface::return_type::ERROR);
}

TEST_F(TestTricycleController, configure_succeeds_when_joints_are_specified)
{
<<<<<<< HEAD
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
rclcpp::Parameter("traction_joint_name", rclcpp::ParameterValue(traction_joint_name)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("steering_joint_name", rclcpp::ParameterValue(steering_joint_name)));
=======
ASSERT_EQ(InitController(), controller_interface::return_type::OK);
>>>>>>> 8d732f1 ([tricycle_controller] Use generate_parameter_library (#957))

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);

Expand All @@ -254,30 +233,15 @@ TEST_F(TestTricycleController, configure_succeeds_when_joints_are_specified)

TEST_F(TestTricycleController, activate_fails_without_resources_assigned)
{
<<<<<<< HEAD
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
rclcpp::Parameter("traction_joint_name", rclcpp::ParameterValue(traction_joint_name)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("steering_joint_name", rclcpp::ParameterValue(steering_joint_name)));
=======
ASSERT_EQ(InitController(), controller_interface::return_type::OK);
>>>>>>> 8d732f1 ([tricycle_controller] Use generate_parameter_library (#957))

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
}

TEST_F(TestTricycleController, activate_succeeds_with_resources_assigned)
{
<<<<<<< HEAD
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);
=======
ASSERT_EQ(InitController(), controller_interface::return_type::OK);
>>>>>>> 8d732f1 ([tricycle_controller] Use generate_parameter_library (#957))

// We implicitly test that by default position feedback is required
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
Expand All @@ -287,23 +251,11 @@ TEST_F(TestTricycleController, activate_succeeds_with_resources_assigned)

TEST_F(TestTricycleController, cleanup)
{
<<<<<<< HEAD
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
rclcpp::Parameter("traction_joint_name", rclcpp::ParameterValue(traction_joint_name)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("steering_joint_name", rclcpp::ParameterValue(steering_joint_name)));
controller_->get_node()->set_parameter(rclcpp::Parameter("wheelbase", 1.2));
controller_->get_node()->set_parameter(rclcpp::Parameter("wheel_radius", 0.12));
=======
ASSERT_EQ(
InitController(
traction_joint_name, steering_joint_name,
{rclcpp::Parameter("wheelbase", 1.2), rclcpp::Parameter("wheel_radius", 0.12)}),
controller_interface::return_type::OK);
>>>>>>> 8d732f1 ([tricycle_controller] Use generate_parameter_library (#957))

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(controller_->get_node()->get_node_base_interface());
Expand Down Expand Up @@ -344,23 +296,11 @@ TEST_F(TestTricycleController, cleanup)

TEST_F(TestTricycleController, correct_initialization_using_parameters)
{
<<<<<<< HEAD
const auto ret = controller_->init(controller_name);
ASSERT_EQ(ret, controller_interface::return_type::OK);

controller_->get_node()->set_parameter(
rclcpp::Parameter("traction_joint_name", rclcpp::ParameterValue(traction_joint_name)));
controller_->get_node()->set_parameter(
rclcpp::Parameter("steering_joint_name", rclcpp::ParameterValue(steering_joint_name)));
controller_->get_node()->set_parameter(rclcpp::Parameter("wheelbase", 0.4));
controller_->get_node()->set_parameter(rclcpp::Parameter("wheel_radius", 1.0));
=======
ASSERT_EQ(
InitController(
traction_joint_name, steering_joint_name,
{rclcpp::Parameter("wheelbase", 0.4), rclcpp::Parameter("wheel_radius", 1.0)}),
controller_interface::return_type::OK);
>>>>>>> 8d732f1 ([tricycle_controller] Use generate_parameter_library (#957))

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(controller_->get_node()->get_node_base_interface());
Expand Down

0 comments on commit eb88798

Please sign in to comment.