Skip to content

Commit

Permalink
pass robot_description at controller init
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar committed Nov 6, 2024
1 parent 8046a1a commit 45e37e9
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -60,9 +60,7 @@ controller_interface::return_type AdmittanceRule::configure(
kinematics_loader_->createUnmanagedInstance(parameters_.kinematics.plugin_name));

if (!kinematics_->initialize(
robot_description,
node->get_node_parameters_interface(),
"kinematics"))
robot_description, node->get_node_parameters_interface(), "kinematics"))
{
return controller_interface::return_type::ERROR;
}
Expand Down
9 changes: 3 additions & 6 deletions admittance_controller/test/test_admittance_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,18 +102,14 @@ class TestableAdmittanceController : public admittance_controller::AdmittanceCon
}
}

private:
const std::string robot_description_ = ros2_control_test_assets::valid_6d_robot_urdf;
const std::string robot_description_semantic_ = ros2_control_test_assets::valid_6d_robot_srdf;
};

class AdmittanceControllerTest : public ::testing::Test
{
public:
static void SetUpTestCase()
{
// rclcpp::init(0, nullptr);
}
static void SetUpTestCase() {}

void SetUp()
{
Expand Down Expand Up @@ -163,7 +159,8 @@ class AdmittanceControllerTest : public ::testing::Test
controller_interface::return_type SetUpControllerCommon(
const std::string & controller_name, const rclcpp::NodeOptions & options)
{
auto result = controller_->init(controller_name, "", 0, "", options);
auto result =
controller_->init(controller_name, controller_->robot_description_, 0, "", options);

controller_->export_reference_interfaces();
assign_interfaces();
Expand Down

0 comments on commit 45e37e9

Please sign in to comment.