Skip to content
Open
Show file tree
Hide file tree
Changes from all 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
24 changes: 24 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,13 @@ Version 1.2 extends the URDF specification with extended joint limits:
- **Deceleration limit**: The `deceleration` attribute specifies the maximum joint deceleration
- **Jerk limit**: The `jerk` attribute specifies the maximum joint jerk (rate of change of acceleration)

Version 1.2 also relaxes some requirements on the existing joint limit attributes:
- `lower` and `upper` are optional for non-`revolute`/non-`prismatic` joints and default to `NaN` when omitted
- for `revolute` and `prismatic` joints, both `lower` and `upper` must be provided
- `effort` and `velocity` become optional and default to infinity when omitted
- `effort`, `velocity`, `acceleration`, `deceleration`, and `jerk` must all be non-negative when provided
- when both are specified, `upper` must be greater than or equal to `lower`

All three attributes are optional and default to infinity (no limit). If `acceleration` is specified but `deceleration` is not, `deceleration` defaults to the acceleration value. All values must be non-negative.

**Extended Joint Limits Example:**
Expand All @@ -132,6 +139,23 @@ All three attributes are optional and default to infinity (no limit). If `accele
| `deceleration` | Maximum joint deceleration (rad/s² or m/s²) | Same as `acceleration`, or infinity if `acceleration` is not set | Must be non-negative |
| `jerk` | Maximum joint jerk (rad/s³ or m/s³) | Infinity | Must be non-negative |

#### Joint Limit Semantics By Version

The parser keeps legacy behavior for older URDF versions and only applies the relaxed defaults starting in version 1.2.

| Attribute | Version 1.0 / 1.1 | Version 1.2 |
|-----------|-------------------|-------------|
| `lower` | Optional, defaults to `0.0` when omitted | Optional for non-revolute/non-prismatic joints, defaults to `NaN` when omitted |
| `upper` | Optional, defaults to `0.0` when omitted | Optional for non-revolute/non-prismatic joints, defaults to `NaN` when omitted |
| `effort` | Required, parsing fails if omitted | Optional, defaults to infinity when omitted |
| `velocity` | Required, parsing fails if omitted | Optional, defaults to infinity when omitted |
| `acceleration` | Ignored with warning if provided | Optional, defaults to infinity when omitted |
| `deceleration` | Ignored with warning if provided | Optional, defaults to `acceleration` if set, otherwise infinity |
| `jerk` | Ignored with warning if provided | Optional, defaults to infinity when omitted |

For all supported versions, invalid numeric values still fail parsing. In version 1.2, negative values for `effort`, `velocity`, `acceleration`, `deceleration`, and `jerk` are rejected.
In version 1.2, `revolute` and `prismatic` joints additionally require both `lower` and `upper`, and `upper` cannot be smaller than `lower`.

#### Compatibility and Parsing Behavior

| Scenario | Behavior |
Expand Down
72 changes: 62 additions & 10 deletions urdf_parser/src/joint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,15 +96,25 @@ bool parseJointDynamics(JointDynamics &jd, tinyxml2::XMLElement* config)

bool parseJointLimits(JointLimits &jl, tinyxml2::XMLElement* config,
const urdf_export_helpers::URDFVersion version,
const std::string& joint_name)
const std::string& joint_name, int joint_type)
{
jl.clear();

// Get lower joint limit
bool lower_pos_limit = true;
bool upper_pos_limit = true;
const char* lower_str = config->Attribute("lower");
if (lower_str == NULL){
CONSOLE_BRIDGE_logDebug("urdfdom.joint_limit: joint [%s] has no lower, defaults to 0", joint_name.c_str());
jl.lower = 0;
if (version.less_than(1, 2))
{
jl.lower = 0.0;
}
else
{
jl.lower = std::numeric_limits<double>::signaling_NaN();
}
CONSOLE_BRIDGE_logInform("urdfdom.joint_limit: joint [%s] has no lower, defaults to %f", joint_name.c_str(), jl.lower);
lower_pos_limit = false;
}
else
{
Expand All @@ -119,8 +129,16 @@ bool parseJointLimits(JointLimits &jl, tinyxml2::XMLElement* config,
// Get upper joint limit
const char* upper_str = config->Attribute("upper");
if (upper_str == NULL){
CONSOLE_BRIDGE_logDebug("urdfdom.joint_limit: joint [%s] has no upper, defaults to 0", joint_name.c_str());
jl.upper = 0;
if (version.less_than(1, 2))
{
jl.upper = 0.0;
}
else
{
jl.upper = std::numeric_limits<double>::signaling_NaN();
}
CONSOLE_BRIDGE_logInform("urdfdom.joint_limit: joint [%s] has no upper position limit, defaults to %f", joint_name.c_str(), jl.upper);
upper_pos_limit = false;
}
else
{
Expand All @@ -132,11 +150,37 @@ bool parseJointLimits(JointLimits &jl, tinyxml2::XMLElement* config,
}
}

if (version.at_least(1, 2))
{
if(!lower_pos_limit || !upper_pos_limit)
{
if (joint_type == Joint::REVOLUTE || joint_type == Joint::PRISMATIC)
{
CONSOLE_BRIDGE_logError("joint [%s]: revolute and prismatic joints must have both lower and upper position limits specified in URDF version 1.2 or later", joint_name.c_str());
return false;
}
}

if (lower_pos_limit && upper_pos_limit && jl.upper < jl.lower)
{
CONSOLE_BRIDGE_logError("joint [%s]: upper position limit (%f) cannot be smaller than lower position limit (%f)", joint_name.c_str(), jl.upper, jl.lower);
return false;
}
}

// Get joint effort limit
const char* effort_str = config->Attribute("effort");
if (effort_str == NULL){
CONSOLE_BRIDGE_logError("joint [%s]: limit has no effort", joint_name.c_str());
return false;
if (version.less_than(1, 2))
{
CONSOLE_BRIDGE_logError("joint [%s]: limit has no effort", joint_name.c_str());
return false;
}
else
{
jl.effort = std::numeric_limits<double>::infinity();
CONSOLE_BRIDGE_logInform("urdfdom.joint_limit: joint [%s] has no effort limit, defaults to %f", joint_name.c_str(), jl.effort);
}
}
else
{
Expand All @@ -156,8 +200,16 @@ bool parseJointLimits(JointLimits &jl, tinyxml2::XMLElement* config,
// Get joint velocity limit
const char* velocity_str = config->Attribute("velocity");
if (velocity_str == NULL){
CONSOLE_BRIDGE_logError("joint [%s]: limit has no velocity", joint_name.c_str());
return false;
if (version.less_than(1, 2))
{
CONSOLE_BRIDGE_logError("joint [%s]: limit has no velocity", joint_name.c_str());
return false;
}
else
{
jl.velocity = std::numeric_limits<double>::infinity();
CONSOLE_BRIDGE_logInform("urdfdom.joint_limit: joint [%s] has no velocity limit, defaults to %f", joint_name.c_str(), jl.velocity);
}
}
else
{
Expand Down Expand Up @@ -543,7 +595,7 @@ bool parseJoint(Joint &joint, tinyxml2::XMLElement* config,
if (limit_xml)
{
joint.limits.reset(new JointLimits());
if (!parseJointLimits(*joint.limits, limit_xml, version, joint.name))
if (!parseJointLimits(*joint.limits, limit_xml, version, joint.name, joint.type))
{
CONSOLE_BRIDGE_logError("Could not parse limit element for joint [%s]", joint.name.c_str());
joint.limits.reset();
Expand Down
Loading
Loading