Skip to content

Commit

Permalink
Update MoveIt! support (#538)
Browse files Browse the repository at this point in the history
Update MoveIt! configurations to new description structure.

Co-authored-by: Luke Dennis <[email protected]>
Co-authored-by: gavanderhoorn <[email protected]>
Co-authored-by: RobertWilbrandt <[email protected]>
  • Loading branch information
4 people authored Jul 21, 2022
1 parent 9d02cca commit c4d07d7
Show file tree
Hide file tree
Showing 232 changed files with 3,865 additions and 1,995 deletions.
33 changes: 5 additions & 28 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -80,22 +80,11 @@ There exist MoveIt! configuration packages for both robots.

For setting up the MoveIt! nodes to allow motion planning run:

```roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch```
```roslaunch ur5_moveit_config moveit_planning_execution.launch```

For starting up RViz with a configuration including the MoveIt! Motion Planning plugin run:

```roslaunch ur5_moveit_config moveit_rviz.launch config:=true```


NOTE:
As MoveIt! seems to have difficulties with finding plans for the UR with full joint limits [-2pi, 2pi], there is a joint_limited version using joint limits restricted to [-pi,pi]. In order to use this joint limited version, simply use the launch file arguments 'limited', i.e.:

```roslaunch ur_bringup ur5_bringup.launch limited:=true robot_ip:=IP_OF_THE_ROBOT [reverse_port:=REVERSE_PORT]```

```roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch limited:=true```

```roslaunch ur5_moveit_config moveit_rviz.launch config:=true```

```roslaunch ur5_moveit_config moveit_rviz.launch```

___Usage with Gazebo Simulation___
There are launch files available to bringup a simulated robot - either UR5 or UR10.
Expand All @@ -105,28 +94,16 @@ Don't forget to source the correct setup shell files and use a new terminal for

To bring up the simulated robot in Gazebo, run:

```roslaunch ur_gazebo ur5.launch```
```roslaunch ur_gazebo ur5_bringup.launch```


___MoveIt! with a simulated robot___
Again, you can use MoveIt! to control the simulated robot.

For setting up the MoveIt! nodes to allow motion planning run:

```roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch sim:=true```
```roslaunch ur5_moveit_config moveit_planning_execution.launch sim:=true```

For starting up RViz with a configuration including the MoveIt! Motion Planning plugin run:

```roslaunch ur5_moveit_config moveit_rviz.launch config:=true```


NOTE:
As MoveIt! seems to have difficulties with finding plans for the UR with full joint limits [-2pi, 2pi], there is a joint_limited version using joint limits restricted to [-pi,pi]. In order to use this joint limited version, simply use the launch file arguments 'limited', i.e.:

```roslaunch ur_gazebo ur5.launch limited:=true```

```roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch sim:=true limited:=true```

```roslaunch ur5_moveit_config moveit_rviz.launch config:=true```


```roslaunch ur5_moveit_config moveit_rviz.launch```
7 changes: 4 additions & 3 deletions universal_robots/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,12 @@

<buildtool_depend>catkin</buildtool_depend>

<exec_depend>ur10_e_moveit_config</exec_depend>
<exec_depend>ur10e_moveit_config</exec_depend>
<exec_depend>ur10_moveit_config</exec_depend>
<exec_depend>ur3_e_moveit_config</exec_depend>
<exec_depend>ur16e_moveit_config</exec_depend>
<exec_depend>ur3e_moveit_config</exec_depend>
<exec_depend>ur3_moveit_config</exec_depend>
<exec_depend>ur5_e_moveit_config</exec_depend>
<exec_depend>ur5e_moveit_config</exec_depend>
<exec_depend>ur5_moveit_config</exec_depend>
<exec_depend>ur_description</exec_depend>
<exec_depend>ur_gazebo</exec_depend>
Expand Down
8 changes: 0 additions & 8 deletions ur10_e_moveit_config/.setup_assistant

This file was deleted.

10 changes: 0 additions & 10 deletions ur10_e_moveit_config/CHANGELOG.rst

This file was deleted.

5 changes: 0 additions & 5 deletions ur10_e_moveit_config/config/kinematics.yaml

This file was deleted.

84 changes: 0 additions & 84 deletions ur10_e_moveit_config/config/ompl_planning.yaml

This file was deleted.

13 changes: 0 additions & 13 deletions ur10_e_moveit_config/launch/default_warehouse_db.launch

This file was deleted.

46 changes: 0 additions & 46 deletions ur10_e_moveit_config/launch/demo.launch

This file was deleted.

16 changes: 0 additions & 16 deletions ur10_e_moveit_config/launch/moveit_rviz.launch

This file was deleted.

This file was deleted.

16 changes: 0 additions & 16 deletions ur10_e_moveit_config/tests/moveit_planning_execution.xml

This file was deleted.

7 changes: 5 additions & 2 deletions ur10_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,11 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur10_robot.urdf.xacro
relative_path: urdf/ur10.xacro
xacro_args: ""
SRDF:
relative_path: config/ur10.srdf
CONFIG:
generated_timestamp: 1413893323
author_name: Felix Exner
author_email: [email protected]
generated_timestamp: 1611154369
18 changes: 18 additions & 0 deletions ur10_moveit_config/config/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
planning_time_limit: 10.0
max_iterations: 200
max_iterations_after_collision_free: 5
smoothness_cost_weight: 0.1
obstacle_cost_weight: 1.0
learning_rate: 0.01
smoothness_cost_velocity: 0.0
smoothness_cost_acceleration: 1.0
smoothness_cost_jerk: 0.0
ridge_factor: 0.01
use_pseudo_inverse: false
pseudo_inverse_ridge_factor: 1e-4
joint_update_limit: 0.1
collision_clearence: 0.2
collision_threshold: 0.07
use_stochastic_descent: true
enable_failure_recovery: true
max_recovery_attempts: 5
11 changes: 0 additions & 11 deletions ur10_moveit_config/config/controllers.yaml

This file was deleted.

6 changes: 3 additions & 3 deletions ur10_moveit_config/config/fake_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,6 @@ controller_list:
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
- name: fake_endeffector_controller
joints:
[]
initial: # Define initial robot poses.
- group: manipulator
pose: home
Loading

0 comments on commit c4d07d7

Please sign in to comment.