Skip to content

Commit

Permalink
Change kEnableTag to kEnableAttribute and other minor typos
Browse files Browse the repository at this point in the history
Co-authored-by: Christoph Fröhlich <[email protected]>
  • Loading branch information
saikishor and christophfroehlich authored Apr 22, 2024
1 parent 68874f5 commit 7725dd7
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions hardware_interface/src/component_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ constexpr const auto kStateInterfaceTag = "state_interface";
constexpr const auto kMinTag = "min";
constexpr const auto kMaxTag = "max";
constexpr const auto kLimitsTag = "limits";
constexpr const auto kEnableTag = "enable";
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 @@ -299,7 +299,7 @@ hardware_interface::InterfaceInfo parse_interfaces_from_xml(
if (limits_it)
{
interface.enable_limits =
parse_bool(get_attribute_value(limits_it, kEnableTag, limits_it->Name()));
parse_bool(get_attribute_value(limits_it, kEnableAttribute, limits_it->Name()));
}

// Optional initial_value attribute
Expand Down Expand Up @@ -351,7 +351,7 @@ ComponentInfo parse_component_from_xml(const tinyxml2::XMLElement * component_it
const auto * limits_it = component_it->FirstChildElement(kLimitsTag);
if (limits_it)
{
enable_limits = parse_bool(get_attribute_value(limits_it, kEnableTag, limits_it->Name()));
enable_limits = parse_bool(get_attribute_value(limits_it, kEnableAttribute, limits_it->Name()));
}

// Parse all command interfaces
Expand Down Expand Up @@ -887,15 +887,15 @@ std::vector<HardwareInfo> parse_control_resources_from_urdf(const std::string &
continue;
}
joint_limits::JointLimits limits;
const bool has_hard_limts = getJointLimits(urdf_joint, limits);
const bool has_hard_limits = getJointLimits(urdf_joint, limits);
if (
!has_hard_limts &&
!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_limts)
if (has_hard_limits)
{
// Take the most restricted one
update_interface_limits(joint.command_interfaces, limits);
Expand Down

0 comments on commit 7725dd7

Please sign in to comment.