Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Parse URDF joint hard limits into the HardwareInfo structure #1472

Merged
Show file tree
Hide file tree
Changes from 23 commits
Commits
Show all changes
36 commits
Select commit Hold shift + click to select a range
f37ae78
Add joint_limits dependency and add limits map to the HardwareInfo st…
saikishor Jan 16, 2024
7d1077a
Retrieve limits from the URDF as well as ros2_control tag from robot_…
saikishor Jan 16, 2024
f43124d
print error and continue instead of throwing exception
saikishor Jan 16, 2024
b39f1cf
Fix the logic of the retrieval of min and max elements
saikishor Jan 16, 2024
f4586f3
update tests adding the limits part
saikishor Jan 16, 2024
aec2e6f
remove limits enforcing when defined under state interface
saikishor Jan 16, 2024
3c7a4d7
add more testing for other cases
saikishor Jan 16, 2024
ce26ef2
added comments to the limits map and removed extra include
saikishor Apr 2, 2024
8e0faba
Added a way to enable and disable the joint interface limits
saikishor Apr 4, 2024
1779bc0
Added tests for the newly added disabling of joint limits
saikishor Apr 4, 2024
d058b8a
Merge branch 'master' into parse_limits_from_urdf_to_hw_info
saikishor Apr 17, 2024
e3847f9
Add the missing limits to the diffbot urdf continuous joints
saikishor Apr 17, 2024
68874f5
Fix formatting changes
saikishor Apr 17, 2024
7725dd7
Change kEnableTag to kEnableAttribute and other minor typos
saikishor Apr 22, 2024
4fd605a
Merge branch 'master' into parse_limits_from_urdf_to_hw_info
saikishor Apr 22, 2024
2016885
Add tests for the acceleration and jerk limits parsing
saikishor Apr 22, 2024
78c80e8
Fix minor bug in the acceleration and deceleration signs
saikishor Apr 22, 2024
98c95fe
Add tests for specific use conditions
saikishor Apr 22, 2024
18fae53
Format error strings
christophfroehlich Apr 22, 2024
6ac3140
Add comment to remove duplicate code
christophfroehlich Apr 22, 2024
a4d98b1
Add another test with different min/max values
christophfroehlich Apr 22, 2024
0784152
Rename tests
christophfroehlich Apr 22, 2024
5e8f3f0
Fix the missing GPIOs part in the tests
saikishor Apr 23, 2024
2f6cf66
Remove unnecessary check and add test if it still throws
christophfroehlich Apr 23, 2024
611e60a
Test if it throws on revolute+prismatic without limits
christophfroehlich Apr 23, 2024
3cfce6b
Fix continuous joint limits
christophfroehlich Apr 23, 2024
9b21ba4
Successfully parse continuous joint limits if set in URDF
christophfroehlich Apr 23, 2024
74e22b9
Throw if trying to configure a fixed joint
christophfroehlich Apr 23, 2024
b414970
Remove duplicate code
christophfroehlich Apr 24, 2024
75731af
Merge branch 'master' into parse_limits_from_urdf_to_hw_info
saikishor Apr 24, 2024
48bbef3
separate the lambdas into isolated helper methods
saikishor May 3, 2024
9d08858
fix the has_limits logic for different interfaces
saikishor May 3, 2024
fbe02b4
Merge branch 'master' into parse_limits_from_urdf_to_hw_info
saikishor May 3, 2024
616b491
make update_interface_limits more generic and fix minor bug
saikishor May 3, 2024
dc0d414
Remove the copy_interface_limits method as generic update_interface_l…
saikishor May 3, 2024
8e0d86e
Merge branch 'master' into parse_limits_from_urdf_to_hw_info
saikishor May 6, 2024
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 hardware_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
rcutils
TinyXML2
tinyxml2_vendor
joint_limits
urdf
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
#include <unordered_map>
#include <vector>

#include "joint_limits/joint_limits.hpp"

namespace hardware_interface
{
/**
Expand All @@ -42,6 +44,8 @@ struct InterfaceInfo
std::string data_type;
/// (Optional) If the handle is an array, the size of the array. Used by GPIOs.
int size;
/// (Optional) enable or disable the limits for the command interfaces
bool enable_limits;
};

/// @brief This structure stores information about a joint that is mimicking another joint
Expand Down Expand Up @@ -163,6 +167,10 @@ struct HardwareInfo
* The XML contents prior to parsing
*/
std::string original_xml;
/**
* The URDF parsed limits of the hardware components joint command interfaces
*/
std::unordered_map<std::string, joint_limits::JointLimits> limits;
};

} // namespace hardware_interface
Expand Down
1 change: 1 addition & 0 deletions hardware_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
<depend>rclcpp_lifecycle</depend>
<depend>rcpputils</depend>
<depend>tinyxml2_vendor</depend>
<depend>joint_limits</depend>
<depend>urdf</depend>

<build_depend>rcutils</build_depend>
Expand Down
191 changes: 189 additions & 2 deletions hardware_interface/src/component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@
#include "hardware_interface/component_parser.hpp"
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/lexical_casts.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "joint_limits/joint_limits_urdf.hpp"

namespace
{
Expand All @@ -43,6 +45,8 @@ constexpr const auto kCommandInterfaceTag = "command_interface";
constexpr const auto kStateInterfaceTag = "state_interface";
constexpr const auto kMinTag = "min";
constexpr const auto kMaxTag = "max";
constexpr const auto kLimitsTag = "limits";
constexpr const auto kEnableAttribute = "enable";
constexpr const auto kInitialValueTag = "initial_value";
constexpr const auto kMimicAttribute = "mimic";
constexpr const auto kDataTypeAttribute = "data_type";
Expand Down Expand Up @@ -289,6 +293,15 @@ hardware_interface::InterfaceInfo parse_interfaces_from_xml(
interface.max = interface_param->second;
}

// Option enable or disable the interface limits, by default they are enabled
interface.enable_limits = true;
const auto * limits_it = interfaces_it->FirstChildElement(kLimitsTag);
if (limits_it)
{
interface.enable_limits =
parse_bool(get_attribute_value(limits_it, kEnableAttribute, limits_it->Name()));
}

// Optional initial_value attribute
interface_param = interface_params.find(kInitialValueTag);
if (interface_param != interface_params.end())
Expand Down Expand Up @@ -333,19 +346,31 @@ ComponentInfo parse_component_from_xml(const tinyxml2::XMLElement * component_it
}
}

// Option enable or disable the interface limits, by default they are enabled
bool enable_limits = true;
const auto * limits_it = component_it->FirstChildElement(kLimitsTag);
if (limits_it)
{
enable_limits = parse_bool(get_attribute_value(limits_it, kEnableAttribute, limits_it->Name()));
}

// Parse all command interfaces
const auto * command_interfaces_it = component_it->FirstChildElement(kCommandInterfaceTag);
while (command_interfaces_it)
{
component.command_interfaces.push_back(parse_interfaces_from_xml(command_interfaces_it));
InterfaceInfo cmd_info = parse_interfaces_from_xml(command_interfaces_it);
cmd_info.enable_limits &= enable_limits;
component.command_interfaces.push_back(cmd_info);
command_interfaces_it = command_interfaces_it->NextSiblingElement(kCommandInterfaceTag);
}

// Parse state interfaces
const auto * state_interfaces_it = component_it->FirstChildElement(kStateInterfaceTag);
while (state_interfaces_it)
{
component.state_interfaces.push_back(parse_interfaces_from_xml(state_interfaces_it));
InterfaceInfo state_info = parse_interfaces_from_xml(state_interfaces_it);
state_info.enable_limits &= enable_limits;
component.state_interfaces.push_back(state_info);
state_interfaces_it = state_interfaces_it->NextSiblingElement(kStateInterfaceTag);
}

Expand Down Expand Up @@ -629,6 +654,144 @@ std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string &
ros2_control_it = ros2_control_it->NextSiblingElement(kROS2ControlTag);
}

// Retrieve the limits from ros2_control command interface tags and override if restrictive
auto update_interface_limits = [](const auto & interfaces, joint_limits::JointLimits & limits)
{
auto retrieve_min_max_interface_values = [](
const auto & itf, double & min, double & max) -> bool
{
try
{
if (itf.min.empty() && itf.max.empty())
{
// If the limits don't exist then return false as they are not retrieved
return false;
}
if (!itf.min.empty())
{
min = hardware_interface::stod(itf.min);
}
if (!itf.max.empty())
{
max = hardware_interface::stod(itf.max);
}
return true;
}
catch (const std::invalid_argument & err)
{
std::cerr << "Error parsing the limits for the interface: " << itf.name
<< " from the tags [" << kMinTag << ": '" << itf.min << "' and " << kMaxTag
<< ": '" << itf.max << "'] within " << kROS2ControlTag
<< " tag inside the URDF. Skipping it" << std::endl;
return false;
}
};
for (auto & itr : interfaces)
{
if (itr.name == hardware_interface::HW_IF_POSITION)
{
limits.has_position_limits &= itr.enable_limits;
if (limits.has_position_limits)
{
double min_pos(limits.min_position), max_pos(limits.max_position);
if (retrieve_min_max_interface_values(itr, min_pos, max_pos))
{
limits.min_position = std::max(min_pos, limits.min_position);
limits.max_position = std::min(max_pos, limits.max_position);
}
}
else
{
limits.min_position = std::numeric_limits<double>::min();
limits.max_position = std::numeric_limits<double>::max();
}
}
else if (itr.name == hardware_interface::HW_IF_VELOCITY)
{
limits.has_velocity_limits &= itr.enable_limits;
if (limits.has_velocity_limits)
{ // Apply the most restrictive one in the case
double min_vel(-limits.max_velocity), max_vel(limits.max_velocity);
if (retrieve_min_max_interface_values(itr, min_vel, max_vel))
{
max_vel = std::min(std::abs(min_vel), max_vel);
limits.max_velocity = std::min(max_vel, limits.max_velocity);
}
}
Copy link
Contributor

Choose a reason for hiding this comment

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

Out of curiosity why you do not do a default initialization of the max_velocity ?

Copy link
Contributor

Choose a reason for hiding this comment

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

what do you mean by default initialization? limits will be filled from the URDF tag, which is mandatory for REVOLUTE and PRISMATIC joints -> max_velocity is already populated

Copy link
Member Author

Choose a reason for hiding this comment

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

Yes, moreover, there might be a joint without velocity limits, so it doesn't make sense

}
else if (itr.name == hardware_interface::HW_IF_EFFORT)
{
limits.has_effort_limits &= itr.enable_limits;
if (limits.has_effort_limits)
{ // Apply the most restrictive one in the case
double min_eff(-limits.max_effort), max_eff(limits.max_effort);
if (retrieve_min_max_interface_values(itr, min_eff, max_eff))
{
max_eff = std::min(std::abs(min_eff), max_eff);
limits.max_effort = std::min(max_eff, limits.max_effort);
}
}
Copy link
Contributor

Choose a reason for hiding this comment

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

Same here wrt to max_effort

Copy link
Member Author

Choose a reason for hiding this comment

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

Well same as above

}
else if (itr.name == hardware_interface::HW_IF_ACCELERATION)
{
double max_decel(std::numeric_limits<double>::quiet_NaN()),
max_accel(std::numeric_limits<double>::quiet_NaN());
if (retrieve_min_max_interface_values(itr, max_decel, max_accel))
{
if (std::isfinite(max_decel))
{
limits.max_deceleration = std::fabs(max_decel);
if (!std::isfinite(max_accel))
{
limits.max_acceleration = std::fabs(limits.max_deceleration);
}
limits.has_deceleration_limits = true && itr.enable_limits;
}
if (std::isfinite(max_accel))
{
limits.max_acceleration = max_accel;

if (!std::isfinite(limits.max_deceleration))
{
limits.max_deceleration = std::fabs(limits.max_acceleration);
}
limits.has_acceleration_limits = true && itr.enable_limits;
}
}
}
else if (itr.name == "jerk")
{
if (!itr.min.empty())
{
std::cerr << "Error parsing the limits for the interface: " << itr.name
<< " from the tag: " << kMinTag << " within " << kROS2ControlTag
<< " tag inside the URDF. Jerk only accepts max limits." << std::endl;
}
double min_jerk(std::numeric_limits<double>::quiet_NaN()),
max_jerk(std::numeric_limits<double>::quiet_NaN());
if (
!itr.max.empty() && retrieve_min_max_interface_values(itr, min_jerk, max_jerk) &&
std::isfinite(max_jerk))
{
limits.max_jerk = std::abs(max_jerk);
limits.has_jerk_limits = true && itr.enable_limits;
}
Copy link
Contributor

Choose a reason for hiding this comment

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

Same here for max_jerk

Copy link
Member Author

Choose a reason for hiding this comment

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

Jerk limits are very familiar as the support in ROS is little, so I think it is better to leave it up to the user

}
else
{
if (!itr.min.empty() || !itr.max.empty())
{
std::cerr << "Unable to parse the limits for the interface: " << itr.name
<< " from the tags [" << kMinTag << " and " << kMaxTag << "] within "
<< kROS2ControlTag
<< " tag inside the URDF. Supported interfaces for joint limits are: "
"position, velocity, effort, acceleration and jerk."
<< std::endl;
}
}
}
};

// parse full URDF for mimic options
urdf::Model model;
if (!model.initString(urdf))
Expand Down Expand Up @@ -716,6 +879,30 @@ std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string &
hw_info.mimic_joints.push_back(mimic_joint);
}
}
// TODO(christophfroehlich) remove this code if deprecated mimic attribute - branch
// from above is removed (double check here, but throws already above if not found in URDF)
auto urdf_joint = model.getJoint(joint.name);
if (!urdf_joint)
{
std::cerr << "Joint : '" + joint.name + "' not found in URDF. Skipping limits parsing!"
<< std::endl;
continue;
}
joint_limits::JointLimits limits;
const bool has_hard_limits = getJointLimits(urdf_joint, limits);
if (
!has_hard_limits &&
(urdf_joint->type == urdf::Joint::REVOLUTE || urdf_joint->type == urdf::Joint::PRISMATIC ||
urdf_joint->type == urdf::Joint::CONTINUOUS))
{
throw std::runtime_error("Missing URDF joint limits for the Joint: " + joint.name);
}
if (has_hard_limits)
{
// Take the most restricted one
update_interface_limits(joint.command_interfaces, limits);
hw_info.limits[joint.name] = limits;
}
}
}

Expand Down
Loading
Loading