No acceleration/velocity limit was defined although they are in joint_limits.yaml
Description
MoveIt2 reports missing acceleration limits for joints, but they are defined in joint_limits.yaml and appear to be loaded correctly in some contexts but not others.
I'm trying to run some trajectories from a node, using MTC and MoveIt. I'm stuck with this error:
[operation_solver-16] [ERROR 1750160894.528105117] [operation_solver.moveit.core.time_optimal_trajectory_generation]: No acceleration limit was defined for joint ur_shoulder_pan_joint! You have to define acceleration limits in the URDF or joint_limits.yaml (computeTimeStamps() at /home/mtorres/ros/motionplanning/src/moveit2/moveit_core/trajectory_processing/src/time_optimal_trajectory_generation.cpp:1001)
[operation_solver-16] [ERROR 1750160894.528108942] [operation_solver.moveit.ros.add_time_optimal_parameterization]: Response adapter 'AddTimeOptimalParameterization' failed to generate a trajectory. (adapt() at /home/mtorres/ros/motionplanning/src/moveit2/moveit_ros/planning/planning_response_adapter_plugins/src/add_time_optimal_parameterization.cpp:93)
[operation_solver-16] [ERROR 1750160894.528201921] [proposal_verifier_thread_0]: PlanningResponseAdapter 'AddTimeOptimalParameterization' failed with error code FAILURE (generatePlan() at /home/mtorres/ros/motionplanning/src/moveit2/moveit_ros/planning/planning_pipeline/src/planning_pipeline.cpp:349)
I've made sure that my joint_limits.yaml has the acceleration limits correctly, e.g.:
joint_limits:
shoulder_pan_joint:
has_acceleration_limits: true
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 330.0
max_acceleration: 0.3
min_position: !degrees -260.0 #-100.0
max_position: !degrees 100.0 # 100.0
max_velocity: !degrees 120.0
In fact, I'm sure that the MoveGroup has access to it as I can log the info below for every joint:
[dynamic_task_planner-13] [INFO 1750160863.386005694] [moveit_1098641325.moveit.ros.robot_model_loader]: Variable: ur_shoulder_pan_joint, pos[-4.537856, 1.745329], vel[-2.094395, 2.094395], acc[-0.300000, 0.300000], bounded: pos=true, vel=true, acc=true (configure() at /home/mtorres/ros/motionplanning/src/moveit2/moveit_ros/planning/robot_model_loader/src/robot_model_loader.cpp:257)
[dynamic_task_planner-13] [INFO 1750160863.386868850] [moveit_1098641325.moveit.ros.robot_model_loader]: Variable: ur_shoulder_lift_joint, pos[-4.188790, 0.174533], vel[-2.094395, 2.094395], acc[-1.000000, 1.000000], bounded: pos=true, vel=true, acc=true (configure() at /home/mtorres/ros/motionplanning/src/moveit2/moveit_ros/planning/robot_model_loader/src/robot_model_loader.cpp:257)
However, when logging the bounds in computeTimeStamps, acceleration bounds are 0, and they are not part of the robot model:
* Variables:
'ewellix_lift_top_joint', index 7 in full state, index 0 in group state
P.bounded [0.00000, 0.50000]; V.bounded [-0.08800, 0.08800]; A.unbounded [0.00000, 0.00000]; J.unbounded [0.00000, 0.00000];
'ur_shoulder_pan_joint', index 8 in full state, index 1 in group state
P.bounded [-4.38786, 1.59533]; V.bounded [-2.09440, 2.09440]; A.unbounded [0.00000, 0.00000]; J.unbounded [0.00000, 0.00000];
'ur_shoulder_lift_joint', index 9 in full state, index 2 in group state
P.bounded [-4.03879, 0.02453]; V.bounded [-2.09440, 2.09440]; A.unbounded [0.00000, 0.00000]; J.unbounded [0.00000, 0.00000];
'ur_elbow_joint', index 10 in full state, index 3 in group state
P.bounded [-2.55526, 2.41563]; V.bounded [-3.14159, 3.14159]; A.unbounded [0.00000, 0.00000]; J.unbounded [0.00000, 0.00000];
.....
[INFO 1750160890.145329477] [operation_solver.moveit.core.time_optimal_trajectory_generation]: Joint: ur_shoulder_pan_joint, bounds: min_velocity=-2.094395, max_velocity=2.094395, min_acceleration=0.000000, max_acceleration=0.000000 (computeTimeStamps() at /home/mtorres/ros/motionplanning/src/moveit2/moveit_core/trajectory_processing/src/time_optimal_trajectory_generation.cpp:959)
Update: No velocity limit was defined
I found out what was happening. I was doing this to create my robot_model:
auto robot_model_loader = std::make_shared<robot_model_loader::RobotModelLoader>(
subnode, std::string("robot_description"));
robot_model_ptr = robot_model_loader->getModel();
And found out that RobotModelLoader uses jointBoundsFromURDF, which only gets velocity and position bounds (MoveIt code).
I thought that it would fix by manually setting the acceleration bounds after creating robot_model_ptr but after doing that, I'm facing another similar error:
[operation_solver-16] [ERROR 1750311720.210807256] [operation_solver.moveit.core.time_optimal_trajectory_generation]: No velocity limit was defined for joint ur_shoulder_pan_joint! You have to define velocity limits in the URDF or joint_limits.yaml (computeTimeStamps() at /home/mtorres/ros/motionplanning/src/moveit2/moveit_core/trajectory_processing/src/time_optimal_trajectory_generation.cpp:978)
However, now I'm sure that the robot_model_ptr has both of them:
[operation_solver-16] Group 'manipulator' using 6 variables
[operation_solver-16] * Joints:
[operation_solver-16] 'ur_base_link-base_link_inertia' (Fixed)
[operation_solver-16] 'ur_shoulder_pan_joint' (Revolute)
[operation_solver-16] 'ur_shoulder_lift_joint' (Revolute)
[operation_solver-16] 'ur_elbow_joint' (Revolute)
[operation_solver-16] 'ur_wrist_1_joint' (Revolute)
[operation_solver-16] 'ur_wrist_2_joint' (Revolute)
[operation_solver-16] 'ur_wrist_3_joint' (Revolute)
[operation_solver-16] 'wrist_extension_joint' (Fixed)
[operation_solver-16] 'tool_changer_joint' (Fixed)
[operation_solver-16] * Variables:
[operation_solver-16] 'ur_shoulder_pan_joint', index 8 in full state, index 0 in group state
[operation_solver-16] P.unbounded [-4.38786, 1.59533]; V.unbounded [-2.0944, 2.0944]; A.bounded [-0.3, 0.3]; J.unbounded [0, 0];
[operation_solver-16] 'ur_shoulder_lift_joint', index 9 in full state, index 1 in group state
[operation_solver-16] P.unbounded [-4.03879, 0.0245329]; V.unbounded [-2.0944, 2.0944]; A.bounded [-1, 1]; J.unbounded [0, 0];
[operation_solver-16] 'ur_elbow_joint', index 10 in full state, index 2 in group state
[operation_solver-16] P.unbounded [-2.55526, 2.41563]; V.unbounded [-3.14159, 3.14159]; A.bounded [-1, 1]; J.unbounded [0, 0];
[operation_solver-16] 'ur_wrist_1_joint', index 11 in full state, index 3 in group state
[operation_solver-16] P.unbounded [-2.59017, 1.1939]; V.unbounded [-3.14159, 3.14159]; A.bounded [-1, 1]; J.unbounded [0, 0];
[operation_solver-16] 'ur_wrist_2_joint', index 12 in full state, index 4 in group state
[operation_solver-16] P.unbounded [-2.85197, 2.93923]; V.unbounded [-3.14159, 3.14159]; A.bounded [-1, 1]; J.unbounded [0, 0];
[operation_solver-16] 'ur_wrist_3_joint', index 13 in full state, index 5 in group state
[operation_solver-16] P.unbounded [-3.11377, -0.0976401]; V.unbounded [-3.14159, 3.14159]; A.bounded [-1, 1]; J.unbounded [0, 0];
[operation_solver-16] * Variables Index List:
[operation_solver-16] 8 9 10 11 12 13 (contiguous)
[operation_solver-16] * Kinematics solver bijection:
[operation_solver-16] 0 1 2 3 4 5
ROS Distro
Humble
OS and version
Ubuntu 22.04
Source or binary build?
Source
If binary, which release version?
No response
If source, which branch?
main
Which RMW are you using?
CycloneDDS
Steps to Reproduce
No acceleration limit was defined
auto robot_model_loader = std::make_shared<robot_model_loader::RobotModelLoader>(
subnode, std::string("robot_description"));
robot_model_ptr = robot_model_loader->getModel();
robot_model_ptr->printModelInfo(std::cout);
robot_model_cache.insert({robot_type_id, robot_model_ptr});
auto current_scene = std::make_shared<planning_scene::PlanningScene>(robot_model_ptr);
// Plan using MTC
UPDATE No velocity limit was defined
auto robot_model_loader = std::make_shared<robot_model_loader::RobotModelLoader>(
subnode, std::string("robot_description"));
robot_model_ptr = robot_model_loader->getModel();
// Set acceleration limits for each joint from joint_limit_params
if (robot_model_ptr)
{
for (const auto& param : joint_limit_params)
{
if (node_->has_parameter(param))
{
rclcpp::Parameter p;
node_->get_parameter(param, p);
// Expecting param like "joint_limits.joint_limits.<joint_name>.max_acceleration"
std::string joint_name;
size_t prefix_pos = param.find("joint_limits.joint_limits.");
if (prefix_pos != std::string::npos)
{
size_t name_start =
prefix_pos + std::string("joint_limits.joint_limits.").length();
size_t name_end = param.find('.', name_start);
if (name_end != std::string::npos)
{
joint_name = param.substr(name_start, name_end - name_start);
}
else
{
joint_name = param.substr(name_start);
}
}
if (!joint_name.empty() && param.find("max_acceleration") != std::string::npos &&
p.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE)
{
double acc_limit = p.as_double();
moveit_msgs::msg::JointLimits limits;
limits.joint_name = joint_name;
limits.has_acceleration_limits = true;
limits.max_acceleration = acc_limit;
auto joint_model = robot_model_ptr->getJointModel(joint_name);
if (joint_model)
{
const_cast<moveit::core::JointModel*>(joint_model)
->setVariableBounds({limits});
}
}
}
}
robot_model_ptr->printModelInfo(std::cout);
robot_model_cache.insert({robot_type_id, robot_model_ptr});
// Plan using MTC
Expected behavior
Obtains joint limits correctly from the robot model generated and generates a trajectory.
Actual behavior
AddTimeOptimalParameterization fails:
[ERROR 1750311720.719098318] [operation_solver.moveit.ros.add_time_optimal_parameterization]: Response adapter 'AddTimeOptimalParameterization' failed to generate a trajectory. (adapt() at /home/mtorres/ros/motionplanning/src/moveit2/moveit_ros/planning/planning_response_adapter_plugins/src/add_time_optimal_parameterization.cpp:112)
[ERROR 1750311720.989726341] [proposal_verifier_thread_0]: PlanningResponseAdapter 'AddTimeOptimalParameterization' failed with error code FAILURE (generatePlan() at /home/mtorres/ros/motionplanning/src/moveit2/moveit_ros/planning/planning_pipeline/src/planning_pipeline.cpp:349)
apparently due to missing acceleration, and after the update velocity, limits, although the robot_model I create and that I add to the PlanningScene does in fact have them.
Backtrace or Console output
No response
I noticed that the joint names you mentioned in your console log have "ur_" in front of them. I am guessing that they have been named that way in the urdf or the xacro file as well. Maybe you can try adding the "ur_" prefix in your joint_limits.yaml as well? For example, in your joint_limits.yaml, "shoulder_pan_joint" will become "ur_shoulder_pan_joint".
I actually forgot to mention that what I'm passing is the joint_limits.yaml, modified to include the ur_ prefix, like this:
joint_limits_ur_yaml = {'joint_limits': {}}
for joint in joint_limits_yaml['joint_limits'].keys():
joint_limits_ur_yaml['joint_limits']['ur_' + joint] = joint_limits_yaml['joint_limits'][joint]
operation_solver_node = Node(
name="operation_solver",
package="operation_solver",
executable="operation_solver",
output="screen",
parameters=[{
"rviz": rviz,
"max_solutions": max_solutions_lc,
"operation_retries": operation_retries_lc,
"robot_description_kinematics": kinematics_yaml,
"joint_limits": joint_limits_ur_yaml,
}],
condition=UnlessCondition(debug),
on_exit=Shutdown(),
)
That said, I doubt these error are caused by this... For instance, regarding the No acceleration defined error, it wouldn't make sense for the velocity to be recognized but not the acceleration, since both are defined in the same file under the same joint names. I really suspect this first issue is related to the use of the jointBoundsFromURDF function.
As for the second issue No velocity defined, I honestly have no idea what's going on. The joint names appear to be correct and the robot_model_ptr I logged seems to contain all the necessary joint limits I need (position, velocity and acceleration).
I really appreciate your comment, @AniketCOAST . If you have any further suggestions, I'd love to hear them! :)
I am facing the same issue here :/ ROS2 Jazzy on Ubuntu 24.04, MoveIt2 installed from binaries
@mjimenezm00 I came across a very similar issue while creating a task constructor node. Only the following helped me: I ran the node from a launch file and handed over the required joint limits to it.
def generate_launch_description():
# get joint limits
joint_limits_yaml = load_file(
moveit_config_package, path.join("config", "joint_limits.yaml")
)
joint_limits = {"robot_description_planning": joint_limits_yaml}
my_node = Node(
package="my_package",
executable="my_node",
output="screen",
parameters=[
joint_limits,
],
)
return LaunchDescription([my_node])
Only then I was able to see the the acceleration limits within the robot model loaded in the node.
[my_node-1] 'joint_6', index 6 in full state, index 6 in group state
[my_node-1] P.bounded [-2.35619, 2.35619]; V.bounded [-2.61, 2.61]; A.bounded [-5, 5]; J.unbounded [0, 0];**
Not sure if this would be applicable in your case (and I haven't tried some of your attempts described above) but maybe this could help...
@robgineer how are you creating the robot model in your node?? Are you using RobotModelLoader with robot_description too?
@mjimenezm00 its loaded using the Task class. Example: https://github.com/moveit/moveit_task_constructor/blob/3b2a436f0a7e8dbb4d347960430bc26183d99535/demo/src/pick_place_task.cpp#L113
I also handed over the robot_description in the Node params. Example: https://github.com/moveit/moveit_task_constructor/blob/3b2a436f0a7e8dbb4d347960430bc26183d99535/demo/launch/run.launch.py#L23
(but this did not seem to have been necessary since I am publishing the robot_description from another Node.
This issue is being labeled as stale because it has been open 45 days with no activity. It will be automatically closed after another 45 days without follow-ups.
This issue was closed because it has been stalled for 45 days with no activity.