Skip to content

joint_limits.yaml - changes don't have any effect on the velocity of the robot in rviz #2198

@RobinHeitz

Description

@RobinHeitz

Description

In my moveit config package, there is an auto-generated file 'joint_limits.yaml'. If i change the values (e.g. factor 10 in velocity), there is no change in the trajectory/ movement of the robot arm in RViz - I expect it to be factor 10 slower. It's probably not an error, but I cannot find proper documentation to setup a MoveGroup-Node correctly to use the joint_limits.yaml (and further down the road: Change velocity and acceleration scaling factors with parameters from a launch file).

Your environment

  • ROS Distro: Humble
  • OS Version: Ubuntu 22.04
  • Moveit: Binary

Steps to reproduce

  • Using MoveGroup-Node, parameters contain the loaded file 'joint_limits.yaml'
  • Later in my cpp-Node, i use the MoveGroupInterface to plan (cartesian) and execute a movement:

Launching MoveGroup-Node

 run_move_group_node_2 = Node(
        package="moveit_ros_move_group",
        executable="move_group",
        # name="move_group_test",
        output="screen",
        arguments = ['--ros-args', '--log-level', 'WARN'],
        parameters=[
            robot_description,
            robot_description_semantic,
            kinematics_yaml,
            joint_limits_yaml,
            ompl_planning_pipeline_config,
            trajectory_execution,
            moveit_controllers,
            planning_scene_monitor_parameters,
        ],
    )

Using MoveGroupInterface:

       std::vector<geometry_msgs::msg::Pose> waypoints;
        geometry_msgs::msg::PoseStamped target_pose;
        target_pose.pose = target;
        target_pose.header.frame_id = end_effector_link;
        waypoints.push_back(target);

        moveit_msgs::msg::RobotTrajectory trajectory;
        const double jump_threshold = 0.0;
        const double eef_step = 0.01;
        double fraction = move_group_interface.computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory); // Fraction refers to planned path coverage. Should be over 100% = 1

        // Execute the plan
        if (fraction >= 1) // fraction = part of planned trajectory (should be 100%)
        {
            RCLCPP_ERROR(LOGGER, "Execute");
            move_group_interface.execute(trajectory);

            return true;

The terminal window outputs move_group-4] [WARN] [1684833457.407691711] [moveit_trajectory_processing.time_optimal_trajectory_generation]: Joint acceleration limits are not defined. Using the default 1 rad/s^2. You can define acceleration limits in the URDF or joint_limits.yaml. indicating that joint_limits.yaml is not loaded at all, since there are joint limits defined:

default_velocity_scaling_factor: 1.0
default_acceleration_scaling_factor: 1.0

joint_limits:
  melfa_1_joint1:
    has_velocity_limits: true
    max_velocity: 6.2831853071795862
    # max_velocity: 0.62831853071795862
    has_acceleration_limits: true
    max_acceleration: 6.2831853071795862
  melfa_1_joint2:
    has_velocity_limits: true
    max_velocity: 6.9987703004972612
    # max_velocity: 0.69987703004972612
    has_acceleration_limits: true
    max_acceleration: 6.9987703004972612
  ...

Expected behaviour

Based on documentation, I expect that 1) the file joint_limits.yaml - file is loaded automatically and overrides (maybe existing) joint limits from the urdf. 2), if changes are made to this file, the trajectory/ movement itself in rviz (and of course the real robot too) should represent these changes.

By default MoveIt sets the joint velocity and acceleration limits of a joint trajectory to the default allowed in the robot’s URDF or joint_limits.yaml. The joint_limits.yaml is generated from the Setup Assistant and is initially an exact copy of the values within the URDF. The user can then modify those values to be less than the original URDF values if special constraints are needed. Specific joint properties can be changed with the keys max_position, min_position, max_velocity, max_acceleration, max_jerk. Joint limits can be turned on or off with the keys has_velocity_limits, has_acceleration_limits, has_jerk_limits.
https://moveit.picknik.ai/humble/doc/examples/time_parameterization/time_parameterization_tutorial.html?highlight=joint_limits

Actual behaviour

Unfortunately, there is no change in the speed whatsoever.

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't working

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions