Skip to content

Commit

Permalink
Merge pull request #518 from gavanderhoorn/gazebo_updates
Browse files Browse the repository at this point in the history
Main improvements:

 - follow ROS-I naming and package layout conventions
 - clean up xacros (naming, whitespace, etc)
 - treat (the virtual robot in) Gazebo as much as possible as just another UR variant (so we get to reuse workflow, settings and `.launch` files as much as possible)
 - improve comments in `.xacro` files
 - clean up "public API" of `ur_gazebo` (ie: `.launch` and `_macro.xacro` files )
  • Loading branch information
gavanderhoorn authored Jul 1, 2020
2 parents 92cf300 + 467042b commit 8e5cc30
Show file tree
Hide file tree
Showing 52 changed files with 1,217 additions and 513 deletions.
11 changes: 9 additions & 2 deletions ur_gazebo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,14 @@ catkin_package()

if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(tests/roslaunch_test.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur3.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur3e.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur5.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur5e.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur10.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur10e.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur16e.xml)
endif()

install(DIRECTORY launch controller urdf DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
install(DIRECTORY config launch urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
29 changes: 29 additions & 0 deletions ur_gazebo/config/ur10_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 125

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
elbow_joint: {trajectory: 0.1, goal: 0.1}
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joints: *robot_joints
29 changes: 29 additions & 0 deletions ur_gazebo/config/ur10e_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 500

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
elbow_joint: {trajectory: 0.1, goal: 0.1}
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joints: *robot_joints
29 changes: 29 additions & 0 deletions ur_gazebo/config/ur16e_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 500

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
elbow_joint: {trajectory: 0.1, goal: 0.1}
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joints: *robot_joints
29 changes: 29 additions & 0 deletions ur_gazebo/config/ur3_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 125

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
elbow_joint: {trajectory: 0.1, goal: 0.1}
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joints: *robot_joints
29 changes: 29 additions & 0 deletions ur_gazebo/config/ur3e_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 500

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
elbow_joint: {trajectory: 0.1, goal: 0.1}
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joints: *robot_joints
29 changes: 29 additions & 0 deletions ur_gazebo/config/ur5_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 125

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
elbow_joint: {trajectory: 0.1, goal: 0.1}
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joints: *robot_joints
29 changes: 29 additions & 0 deletions ur_gazebo/config/ur5e_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: &loop_hz 500

pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
elbow_joint: {trajectory: 0.1, goal: 0.1}
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: *loop_hz
action_monitor_rate: 10

joint_group_pos_controller:
type: position_controllers/JointGroupPositionController
joints: *robot_joints
31 changes: 0 additions & 31 deletions ur_gazebo/controller/arm_controller_ur10.yaml

This file was deleted.

31 changes: 0 additions & 31 deletions ur_gazebo/controller/arm_controller_ur16.yaml

This file was deleted.

31 changes: 0 additions & 31 deletions ur_gazebo/controller/arm_controller_ur3.yaml

This file was deleted.

31 changes: 0 additions & 31 deletions ur_gazebo/controller/arm_controller_ur5.yaml

This file was deleted.

3 changes: 0 additions & 3 deletions ur_gazebo/controller/joint_state_controller.yaml

This file was deleted.

18 changes: 0 additions & 18 deletions ur_gazebo/launch/controller_utils.launch

This file was deleted.

Loading

0 comments on commit 8e5cc30

Please sign in to comment.