-
Notifications
You must be signed in to change notification settings - Fork 303
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
Changes from 23 commits
f37ae78
7d1077a
f43124d
b39f1cf
f4586f3
aec2e6f
3c7a4d7
ce26ef2
8e0faba
1779bc0
d058b8a
e3847f9
68874f5
7725dd7
4fd605a
2016885
78c80e8
98c95fe
18fae53
6ac3140
a4d98b1
0784152
5e8f3f0
2f6cf66
611e60a
3cfce6b
9b21ba4
74e22b9
b414970
75731af
48bbef3
9d08858
fbe02b4
616b491
dc0d414
8e0d86e
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -15,6 +15,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS | |
rcutils | ||
TinyXML2 | ||
tinyxml2_vendor | ||
joint_limits | ||
urdf | ||
) | ||
|
||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -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 | ||
{ | ||
|
@@ -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"; | ||
|
@@ -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()) | ||
|
@@ -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); | ||
} | ||
|
||
|
@@ -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); | ||
} | ||
} | ||
} | ||
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); | ||
} | ||
} | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Same here wrt to There was a problem hiding this comment. Choose a reason for hiding this commentThe 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; | ||
} | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Same here for There was a problem hiding this comment. Choose a reason for hiding this commentThe 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)) | ||
|
@@ -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; | ||
} | ||
} | ||
} | ||
|
||
|
There was a problem hiding this comment.
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 ?
There was a problem hiding this comment.
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 populatedThere was a problem hiding this comment.
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