Skip to content
Open
Show file tree
Hide file tree
Changes from 4 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
1 change: 1 addition & 0 deletions admittance_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
tf2_geometry_msgs
tf2_kdl
tf2_ros
tinyxml2
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

   --- stderr: admittance_controller
  CMake Error at CMakeLists.txt:33 (find_package):
    By not providing "Findtinyxml2.cmake" in CMAKE_MODULE_PATH this project has
    asked CMake to find a package configuration file provided by "tinyxml2",
    but CMake did not find one.
  
    Could not find a package configuration file provided by "tinyxml2" with any
    of the following names:
  
      tinyxml2Config.cmake
      tinyxml2-config.cmake
  
    Add the installation prefix of "tinyxml2" to CMAKE_PREFIX_PATH or set
    "tinyxml2_DIR" to a directory containing one of the above files.  If
    "tinyxml2" provides a separate development package or SDK, be sure it has
    been installed.
  
  
  ---

But it works here
https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/CMakeLists.txt#L16
with the capitalized version

Suggested change
tinyxml2
TinyXML2

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

And please add to target_link_libraries below:

                  ${TinyXML2_LIBRARIES}

trajectory_msgs
)

Expand Down
1 change: 1 addition & 0 deletions admittance_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
<depend>tf2_kdl</depend>
<depend>tf2_ros</depend>
<depend>tf2</depend>
<depend>tinyxml2</depend>
<depend>trajectory_msgs</depend>

<test_depend>ament_cmake_gmock</test_depend>
Expand Down
28 changes: 28 additions & 0 deletions admittance_controller/src/admittance_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include "admittance_controller/admittance_controller.hpp"

#include <tinyxml2.h>
#include <cmath>
#include <memory>
#include <string>
Expand Down Expand Up @@ -92,6 +93,33 @@ controller_interface::CallbackReturn AdmittanceController::on_init()
reference_admittance_ = last_reference_;
joint_state_ = last_reference_;

std::string robot_description = this->get_robot_description();

if (robot_description.empty())
{
RCLCPP_ERROR(get_node()->get_logger(), "'robot_description' parameter is empty.");
return controller_interface::CallbackReturn::ERROR;
}

tinyxml2::XMLDocument doc;
if (!doc.Parse(robot_description.c_str()) && doc.Error())
{
RCLCPP_ERROR(
get_node()->get_logger(),
"Failed to parse robot description XML from parameter "
"'robot_description': %s",
doc.ErrorStr());
return controller_interface::CallbackReturn::ERROR;
}
if (doc.Error())
{
RCLCPP_ERROR(
get_node()->get_logger(),
"Error parsing robot description XML from parameter "
"'robot_description': %s",
doc.ErrorStr());
return controller_interface::CallbackReturn::ERROR;
}
return controller_interface::CallbackReturn::SUCCESS;
}

Expand Down
8 changes: 3 additions & 5 deletions admittance_controller/test/test_admittance_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,12 +62,10 @@ INSTANTIATE_TEST_SUITE_P(
// wrong length selected axes
std::make_tuple(
std::string("admittance.selected_axes"),
rclcpp::ParameterValue(std::vector<double>() = {1, 2, 3}))
rclcpp::ParameterValue(std::vector<double>() = {1, 2, 3})),
// invalid robot description.
// TODO(anyone): deactivated, because SetUpController returns SUCCESS here?
// ,std::make_tuple(
// std::string("robot_description"), rclcpp::ParameterValue(std::string() = "bad_robot")))
));
std::make_tuple(
std::string("robot_description"), rclcpp::ParameterValue(std::string() = "bad_robot"))));

// Test on_init returns ERROR when a parameter is invalid
TEST_P(AdmittanceControllerTestParameterizedInvalidParameters, invalid_parameters)
Expand Down
10 changes: 6 additions & 4 deletions admittance_controller/test/test_admittance_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,10 +76,14 @@ class TestableAdmittanceController : public admittance_controller::AdmittanceCon
public:
CallbackReturn on_init() override
{
get_node()->declare_parameter("robot_description", rclcpp::ParameterType::PARAMETER_STRING);
if (!get_node()->has_parameter("robot_description"))
{
get_node()->declare_parameter("robot_description", rclcpp::ParameterType::PARAMETER_STRING);
get_node()->set_parameter({"robot_description", robot_description_});
}

get_node()->declare_parameter(
"robot_description_semantic", rclcpp::ParameterType::PARAMETER_STRING);
get_node()->set_parameter({"robot_description", robot_description_});
get_node()->set_parameter({"robot_description_semantic", robot_description_semantic_});

return admittance_controller::AdmittanceController::on_init();
Expand Down Expand Up @@ -384,8 +388,6 @@ class AdmittanceControllerTest : public ::testing::Test
const std::string ik_base_frame_ = "base_link";
const std::string ik_tip_frame_ = "tool0";
const std::string ik_group_name_ = "arm";
// 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;

const std::string control_frame_ = "tool0";
const std::string endeffector_frame_ = "endeffector_frame";
Expand Down