diff --git a/universal_robots/package.xml b/universal_robots/package.xml index 26caecd0c..0593da5df 100644 --- a/universal_robots/package.xml +++ b/universal_robots/package.xml @@ -24,7 +24,7 @@ ur10_moveit_config ur3e_moveit_config ur3_moveit_config - ur5_e_moveit_config + ur5e_moveit_config ur5_moveit_config ur_description ur_gazebo diff --git a/ur5_e_moveit_config/.setup_assistant b/ur5_e_moveit_config/.setup_assistant deleted file mode 100644 index dd22d1333..000000000 --- a/ur5_e_moveit_config/.setup_assistant +++ /dev/null @@ -1,8 +0,0 @@ -moveit_setup_assistant_config: - URDF: - package: ur_e_description - relative_path: urdf/ur5e_robot.urdf.xacro - SRDF: - relative_path: config/ur5e.srdf - CONFIG: - generated_timestamp: 1413877529 diff --git a/ur5_e_moveit_config/config/controllers.yaml b/ur5_e_moveit_config/config/controllers.yaml deleted file mode 100644 index bf2252cb2..000000000 --- a/ur5_e_moveit_config/config/controllers.yaml +++ /dev/null @@ -1,11 +0,0 @@ -controller_list: - - name: "" - action_ns: follow_joint_trajectory - type: FollowJointTrajectory - joints: - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint diff --git a/ur5_e_moveit_config/config/ompl_planning.yaml b/ur5_e_moveit_config/config/ompl_planning.yaml deleted file mode 100644 index 191879b4e..000000000 --- a/ur5_e_moveit_config/config/ompl_planning.yaml +++ /dev/null @@ -1,84 +0,0 @@ -planner_configs: - SBLkConfigDefault: - type: geometric::SBL - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - ESTkConfigDefault: - type: geometric::EST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LBKPIECEkConfigDefault: - type: geometric::LBKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - BKPIECEkConfigDefault: - type: geometric::BKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - KPIECEkConfigDefault: - type: geometric::KPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - RRTkConfigDefault: - type: geometric::RRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - RRTConnectkConfigDefault: - type: geometric::RRTConnect - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - RRTstarkConfigDefault: - type: geometric::RRTstar - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 - TRRTkConfigDefault: - type: geometric::TRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - max_states_failed: 10 # when to start increasing temp. default: 10 - temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 - min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 - init_temperature: 10e-6 # initial temperature. default: 10e-6 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() - PRMkConfigDefault: - type: geometric::PRM - max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 - PRMstarkConfigDefault: - type: geometric::PRMstar -manipulator: - default_planner_config: RRTConnectkConfigDefault - planner_configs: - - SBLkConfigDefault - - ESTkConfigDefault - - LBKPIECEkConfigDefault - - BKPIECEkConfigDefault - - KPIECEkConfigDefault - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault - ##Note: commenting the following line lets moveit chose RRTConnect as default planner rather than LBKPIECE - #projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) - longest_valid_segment_fraction: 0.01 -endeffector: - planner_configs: - - SBLkConfigDefault - - ESTkConfigDefault - - LBKPIECEkConfigDefault - - BKPIECEkConfigDefault - - KPIECEkConfigDefault - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault diff --git a/ur5_e_moveit_config/launch/default_warehouse_db.launch b/ur5_e_moveit_config/launch/default_warehouse_db.launch deleted file mode 100644 index 626b22f68..000000000 --- a/ur5_e_moveit_config/launch/default_warehouse_db.launch +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/ur5_e_moveit_config/launch/demo.launch b/ur5_e_moveit_config/launch/demo.launch deleted file mode 100644 index dd23ff7d8..000000000 --- a/ur5_e_moveit_config/launch/demo.launch +++ /dev/null @@ -1,46 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - [/move_group/fake_controller_joint_states] - - - - - - - - - - - - - - - - - - - - - - - diff --git a/ur5_e_moveit_config/launch/moveit.rviz b/ur5_e_moveit_config/launch/moveit.rviz deleted file mode 100644 index c7540069f..000000000 --- a/ur5_e_moveit_config/launch/moveit.rviz +++ /dev/null @@ -1,290 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 75 - Name: Displays - Property Tree Widget: - Expanded: - - /MotionPlanning1 - Splitter Ratio: 0.5 - Tree Height: 299 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.588679 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: "" -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.03 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Class: moveit_rviz_plugin/MotionPlanning - Enabled: true - Move Group Namespace: "" - MoveIt_Goal_Tolerance: 0 - MoveIt_Planning_Attempts: 10 - MoveIt_Planning_Time: 5 - MoveIt_Use_Constraint_Aware_IK: true - MoveIt_Warehouse_Host: 127.0.0.1 - MoveIt_Warehouse_Port: 33829 - MoveIt_Workspace: - Center: - X: 0 - Y: 0 - Z: 0 - Size: - X: 2 - Y: 2 - Z: 2 - Name: MotionPlanning - Planned Path: - Color Enabled: false - Interrupt Display: false - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - base: - Alpha: 1 - Show Axes: false - Show Trail: false - base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - ee_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - shoulder_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - tool0: - Alpha: 1 - Show Axes: false - Show Trail: false - upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - world: - Alpha: 1 - Show Axes: false - Show Trail: false - wrist_1_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wrist_2_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wrist_3_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Loop Animation: false - Robot Alpha: 0.5 - Robot Color: 150; 50; 150 - Show Robot Collision: false - Show Robot Visual: true - Show Trail: false - State Display Time: 0.05 s - Trajectory Topic: /move_group/display_planned_path - Planning Metrics: - Payload: 1 - Show Joint Torques: false - Show Manipulability: false - Show Manipulability Index: false - Show Weight Limit: false - TextHeight: 0.08 - Planning Request: - Colliding Link Color: 255; 0; 0 - Goal State Alpha: 1 - Goal State Color: 250; 128; 0 - Interactive Marker Size: 0.15 - Joint Violation Color: 255; 0; 255 - Planning Group: manipulator - Query Goal State: true - Query Start State: false - Show Workspace: false - Start State Alpha: 1 - Start State Color: 0; 255; 0 - Planning Scene Topic: move_group/monitored_planning_scene - Robot Description: robot_description - Scene Geometry: - Scene Alpha: 0.9 - Scene Color: 50; 230; 50 - Scene Display Time: 0.2 - Show Scene Geometry: true - Voxel Coloring: Z-Axis - Voxel Rendering: Occupied Voxels - Scene Robot: - Attached Body Color: 150; 50; 150 - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - base: - Alpha: 1 - Show Axes: false - Show Trail: false - base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - ee_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - shoulder_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - tool0: - Alpha: 1 - Show Axes: false - Show Trail: false - upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - world: - Alpha: 1 - Show Axes: false - Show Trail: false - wrist_1_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wrist_2_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wrist_3_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Robot Alpha: 1 - Show Robot Collision: false - Show Robot Visual: true - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: world - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Topic: /initialpose - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint - Single click: true - Topic: /clicked_point - Value: true - Views: - Current: - Class: rviz/Orbit - Distance: 2.82854 - Enable Stereo Rendering: - Stereo Eye Separation: 0.06 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0.044143 - Y: -0.0136969 - Z: 0.0199439 - Name: Current View - Near Clip Distance: 0.01 - Pitch: 0.465398 - Target Frame: - Value: Orbit (rviz) - Yaw: 0.9954 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 997 - Hide Left Dock: false - Hide Right Dock: true - Motion Planning: - collapsed: false - QMainWindow State: 000000ff00000000fd00000004000000000000027e0000038afc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006300fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001b9000000d900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e006701000001fc000001cb000001c000ffffff000000010000010f000002affc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002af000000af00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650000000000000004b00000022a00fffffffb0000000800540069006d006501000000000000045000000000000000000000040c0000038a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: true - Width: 1680 - X: -10 - Y: 21 diff --git a/ur5_e_moveit_config/launch/moveit_rviz.launch b/ur5_e_moveit_config/launch/moveit_rviz.launch deleted file mode 100644 index a1cb30986..000000000 --- a/ur5_e_moveit_config/launch/moveit_rviz.launch +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/ur5_e_moveit_config/tests/moveit_planning_execution.xml b/ur5_e_moveit_config/tests/moveit_planning_execution.xml deleted file mode 100644 index 53f6e391f..000000000 --- a/ur5_e_moveit_config/tests/moveit_planning_execution.xml +++ /dev/null @@ -1,18 +0,0 @@ - - - - - - - - - - - - - - - - - - diff --git a/ur5e_moveit_config/.setup_assistant b/ur5e_moveit_config/.setup_assistant new file mode 100644 index 000000000..3fae5acd7 --- /dev/null +++ b/ur5e_moveit_config/.setup_assistant @@ -0,0 +1,11 @@ +moveit_setup_assistant_config: + URDF: + package: ur_description + relative_path: urdf/ur5e.xacro + xacro_args: "" + SRDF: + relative_path: config/ur5e.srdf + CONFIG: + author_name: Felix Exner + author_email: felix@fexner.de + generated_timestamp: 1611154369 \ No newline at end of file diff --git a/ur5e_moveit_config/CHANGELOG.rst b/ur5e_moveit_config/CHANGELOG.rst new file mode 100644 index 000000000..28eb11545 --- /dev/null +++ b/ur5e_moveit_config/CHANGELOG.rst @@ -0,0 +1,63 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package ur5e_moveit_config +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.2.5 (2019-04-05) +------------------ +* Update maintainer listing: add Miguel (`#410 `_) +* MoveGroupExecuteService is Deprecated by MoveIt! (`#391 `_) +* Update maintainer and author information. +* Add roslaunch tests (`#362 `_) +* Contributors: gavanderhoorn, Nadia Hammoudeh García, 薯片半价 + +1.2.1 (2018-01-06) +------------------ +* Reduce longest valid segment fraction to accomodate non-limited version of the UR5 (`#266 `_) +* Contributors: Scott Paulin + +1.2.0 (2017-08-04) +------------------ +* Fix Deprecated warning in MoveIt: parameter moved into namespace 'trajectory_execution' +* Contributors: Dave Coleman + +1.1.9 (2017-01-02) +------------------ +* use '--inorder' for jade+ xacro as well. +* make RViz load MoveIt display by default. +* Contributors: gavanderhoorn + +1.1.8 (2016-12-30) +------------------ +* all: update maintainers. +* Contributors: gavanderhoorn + +1.1.7 (2016-12-29) +------------------ +* Don't depend on moveit_plugins metapackage +* Fix xacro warnings in Jade +* Contributors: Dave Coleman, Jon Binney + +1.1.6 (2016-04-01) +------------------ +* add missing dependency for moveit_simple_controller_manager +* Merge branch 'indigo-devel' of github.com:ros-industrial/universal_robot into ur3_moveit_config +* apply latest setup assistant changes to ur5 and ur5e +* Adding comment explaining the choice of default planning algorithm +* Use RRTConnect by default for UR10 + Fixes bug `#193 `_ about slow planning on Indigo + LBKPIECE1 (the previous default) looks to be the wrong planning algorithm for the robot + See https://groups.google.com/forum/#!topic/moveit-users/M71T-GaUNgg +* crop ik solutions wrt joint_limits +* set planning time to 0 +* reduce planning attempts in moveit rviz plugin +* Contributors: Marco Esposito, ipa-fxm + +1.0.2 (2014-03-31) +------------------ + +1.0.1 (2014-03-31) +------------------ +* changes due to file renaming +* update moveit_configs: include ee_link and handle limited robot +* new moveit_configs for ur5 and ur5e +* Contributors: ipa-fxm diff --git a/ur5_e_moveit_config/CMakeLists.txt b/ur5e_moveit_config/CMakeLists.txt similarity index 92% rename from ur5_e_moveit_config/CMakeLists.txt rename to ur5e_moveit_config/CMakeLists.txt index 9bb160b82..3934cf1c7 100644 --- a/ur5_e_moveit_config/CMakeLists.txt +++ b/ur5e_moveit_config/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 2.8.3) -project(ur5_e_moveit_config) +project(ur5e_moveit_config) find_package(catkin REQUIRED) diff --git a/ur5e_moveit_config/config/chomp_planning.yaml b/ur5e_moveit_config/config/chomp_planning.yaml new file mode 100644 index 000000000..75258e53e --- /dev/null +++ b/ur5e_moveit_config/config/chomp_planning.yaml @@ -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 \ No newline at end of file diff --git a/ur5_e_moveit_config/config/fake_controllers.yaml b/ur5e_moveit_config/config/fake_controllers.yaml similarity index 75% rename from ur5_e_moveit_config/config/fake_controllers.yaml rename to ur5e_moveit_config/config/fake_controllers.yaml index 5e24f9451..e328e94d4 100644 --- a/ur5_e_moveit_config/config/fake_controllers.yaml +++ b/ur5e_moveit_config/config/fake_controllers.yaml @@ -9,4 +9,7 @@ controller_list: - wrist_3_joint - name: fake_endeffector_controller joints: - [] \ No newline at end of file + [] +initial: # Define initial robot poses. + - group: manipulator + pose: home \ No newline at end of file diff --git a/ur5_e_moveit_config/config/joint_limits.yaml b/ur5e_moveit_config/config/joint_limits.yaml similarity index 51% rename from ur5_e_moveit_config/config/joint_limits.yaml rename to ur5e_moveit_config/config/joint_limits.yaml index 991719a66..633b7bbce 100644 --- a/ur5_e_moveit_config/config/joint_limits.yaml +++ b/ur5e_moveit_config/config/joint_limits.yaml @@ -2,33 +2,33 @@ # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] joint_limits: - shoulder_pan_joint: + elbow_joint: has_velocity_limits: true - max_velocity: 3.14 - has_acceleration_limits: true - max_acceleration: 3.14 + max_velocity: 3.1415926535897931 + has_acceleration_limits: false + max_acceleration: 0 shoulder_lift_joint: has_velocity_limits: true - max_velocity: 3.14 - has_acceleration_limits: true - max_acceleration: 3.14 - elbow_joint: + max_velocity: 2.0943951023931953 + has_acceleration_limits: false + max_acceleration: 0 + shoulder_pan_joint: has_velocity_limits: true - max_velocity: 3.14 - has_acceleration_limits: true - max_acceleration: 3.14 + max_velocity: 2.0943951023931953 + has_acceleration_limits: false + max_acceleration: 0 wrist_1_joint: has_velocity_limits: true - max_velocity: 6.28 - has_acceleration_limits: true - max_acceleration: 3.14 + max_velocity: 3.1415926535897931 + has_acceleration_limits: false + max_acceleration: 0 wrist_2_joint: has_velocity_limits: true - max_velocity: 6.28 - has_acceleration_limits: true - max_acceleration: 3.14 + max_velocity: 3.1415926535897931 + has_acceleration_limits: false + max_acceleration: 0 wrist_3_joint: has_velocity_limits: true - max_velocity: 6.28 - has_acceleration_limits: true - max_acceleration: 3.14 + max_velocity: 3.1415926535897931 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/ur5_e_moveit_config/config/kinematics.yaml b/ur5e_moveit_config/config/kinematics.yaml similarity index 50% rename from ur5_e_moveit_config/config/kinematics.yaml rename to ur5e_moveit_config/config/kinematics.yaml index 5d492ac1f..e37d336c3 100644 --- a/ur5_e_moveit_config/config/kinematics.yaml +++ b/ur5e_moveit_config/config/kinematics.yaml @@ -1,3 +1,8 @@ +#manipulator: +# kinematics_solver: ur_kinematics/UR10KinematicsPlugin +# kinematics_solver_search_resolution: 0.005 +# kinematics_solver_timeout: 0.005 +# kinematics_solver_attempts: 3 manipulator: kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver_search_resolution: 0.005 diff --git a/ur5e_moveit_config/config/ompl_planning.yaml b/ur5e_moveit_config/config/ompl_planning.yaml new file mode 100644 index 000000000..acbf6bd9b --- /dev/null +++ b/ur5e_moveit_config/config/ompl_planning.yaml @@ -0,0 +1,172 @@ +planner_configs: + SBL: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + EST: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECE: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECE: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECE: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRT: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnect: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstar: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRT: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() + PRM: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstar: + type: geometric::PRMstar + FMT: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMT: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDST: + type: geometric::PDST + STRIDE: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRT: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRT: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiEST: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjEST: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRM: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstar: + type: geometric::LazyPRMstar + SPARS: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwo: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 +manipulator: + planner_configs: + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo +endeffector: + planner_configs: + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo diff --git a/ur5e_moveit_config/config/ros_controllers.yaml b/ur5e_moveit_config/config/ros_controllers.yaml new file mode 100644 index 000000000..0ecf90959 --- /dev/null +++ b/ur5e_moveit_config/config/ros_controllers.yaml @@ -0,0 +1,34 @@ +# Simulation settings for using moveit_sim_controllers +moveit_sim_hw_interface: + joint_model_group: manipulator + joint_model_group_pose: home +# Settings for ros_control_boilerplate control loop +generic_hw_control_loop: + loop_hz: 300 + cycle_time_error_threshold: 0.01 +# Settings for ros_control hardware interface +hardware_interface: + joints: + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint + sim_control_mode: 1 # 0: position, 1: velocity +# Publish all joint states +# Creates the /joint_states topic necessary in ROS +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 +controller_list: +- name: "scaled_pos_joint_traj_controller" + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + joints: + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint diff --git a/ur5_e_moveit_config/config/ur5e.srdf b/ur5e_moveit_config/config/ur5e.srdf similarity index 83% rename from ur5_e_moveit_config/config/ur5e.srdf rename to ur5e_moveit_config/config/ur5e.srdf index bb009a906..76bc9d0b8 100644 --- a/ur5_e_moveit_config/config/ur5e.srdf +++ b/ur5e_moveit_config/config/ur5e.srdf @@ -3,17 +3,17 @@ This is a format for representing semantic information about the robot structure. A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined --> - + - + - + @@ -33,17 +33,18 @@ - + - - - - + + + + + diff --git a/ur5e_moveit_config/launch/chomp_planning_pipeline.launch.xml b/ur5e_moveit_config/launch/chomp_planning_pipeline.launch.xml new file mode 100644 index 000000000..ed0bc619d --- /dev/null +++ b/ur5e_moveit_config/launch/chomp_planning_pipeline.launch.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + diff --git a/ur5e_moveit_config/launch/default_warehouse_db.launch b/ur5e_moveit_config/launch/default_warehouse_db.launch new file mode 100644 index 000000000..c4baf5d47 --- /dev/null +++ b/ur5e_moveit_config/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ur5e_moveit_config/launch/demo.launch b/ur5e_moveit_config/launch/demo.launch new file mode 100644 index 000000000..d00d93522 --- /dev/null +++ b/ur5e_moveit_config/launch/demo.launch @@ -0,0 +1,63 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + + + [move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ur5_e_moveit_config/launch/fake_moveit_controller_manager.launch.xml b/ur5e_moveit_config/launch/fake_moveit_controller_manager.launch.xml similarity index 78% rename from ur5_e_moveit_config/launch/fake_moveit_controller_manager.launch.xml rename to ur5e_moveit_config/launch/fake_moveit_controller_manager.launch.xml index 8a8e020d7..0e7d73907 100644 --- a/ur5_e_moveit_config/launch/fake_moveit_controller_manager.launch.xml +++ b/ur5e_moveit_config/launch/fake_moveit_controller_manager.launch.xml @@ -4,6 +4,6 @@ - + diff --git a/ur5_e_moveit_config/launch/move_group.launch b/ur5e_moveit_config/launch/move_group.launch similarity index 54% rename from ur5_e_moveit_config/launch/move_group.launch rename to ur5e_moveit_config/launch/move_group.launch index d39c94716..764c400bf 100644 --- a/ur5_e_moveit_config/launch/move_group.launch +++ b/ur5e_moveit_config/launch/move_group.launch @@ -1,14 +1,10 @@ - - - - - - + @@ -16,27 +12,52 @@ + + + + + + + + + + + + + + + - - + + - + - + - - + + @@ -47,19 +68,9 @@ + + - - diff --git a/ur5e_moveit_config/launch/moveit.rviz b/ur5e_moveit_config/launch/moveit.rviz new file mode 100644 index 000000000..b431b2a03 --- /dev/null +++ b/ur5e_moveit_config/launch/moveit.rviz @@ -0,0 +1,689 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.74256 + Tree Height: 664 + - Class: rviz/Help + Name: Help + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + MoveIt_Goal_Tolerance: 0 + MoveIt_Planning_Time: 5 + MoveIt_Use_Constraint_Aware_IK: true + MoveIt_Warehouse_Host: 127.0.0.1 + MoveIt_Warehouse_Port: 33829 + Name: MotionPlanning + Planned Path: + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Loop Animation: true + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trajectory Topic: move_group/display_planned_path + Planning Metrics: + Payload: 1 + Show Joint Torques: false + Show Manipulability: false + Show Manipulability Index: false + Show Weight Limit: false + Planning Request: + Colliding Link Color: 255; 0; 0 + Goal State Alpha: 1 + Goal State Color: 250; 128; 0 + Interactive Marker Size: 0 + Joint Violation Color: 255; 0; 255 + Planning Group: left_arm + Query Goal State: true + Query Start State: false + Show Workspace: false + Start State Alpha: 1 + Start State Color: 0; 255; 0 + Planning Scene Topic: move_group/monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Color: 50; 230; 50 + Scene Display Time: 0.2 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Robot Alpha: 0.5 + Show Scene Robot: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/XYOrbit + Distance: 2.9965 + Focal Point: + X: 0.113567 + Y: 0.10592 + Z: 2.23518e-07 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.509797 + Target Frame: /base_link + Value: XYOrbit (rviz) + Yaw: 5.65995 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1337 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + Motion Planning: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004bcfc0200000005fb000000100044006900730070006c00610079007301000000410000032d000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000017400ffffff0000047a000004bc00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1828 + X: 459 + Y: -243 diff --git a/ur5e_moveit_config/launch/moveit_rviz.launch b/ur5e_moveit_config/launch/moveit_rviz.launch new file mode 100644 index 000000000..a4605c037 --- /dev/null +++ b/ur5e_moveit_config/launch/moveit_rviz.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + diff --git a/ur5_e_moveit_config/launch/ompl_planning_pipeline.launch.xml b/ur5e_moveit_config/launch/ompl_planning_pipeline.launch.xml similarity index 90% rename from ur5_e_moveit_config/launch/ompl_planning_pipeline.launch.xml rename to ur5e_moveit_config/launch/ompl_planning_pipeline.launch.xml index eb0ef8926..7ec6880f1 100644 --- a/ur5_e_moveit_config/launch/ompl_planning_pipeline.launch.xml +++ b/ur5e_moveit_config/launch/ompl_planning_pipeline.launch.xml @@ -3,7 +3,7 @@ - - + diff --git a/ur5_e_moveit_config/launch/planning_context.launch b/ur5e_moveit_config/launch/planning_context.launch similarity index 55% rename from ur5_e_moveit_config/launch/planning_context.launch rename to ur5e_moveit_config/launch/planning_context.launch index 63109be0a..9052fd96f 100644 --- a/ur5_e_moveit_config/launch/planning_context.launch +++ b/ur5e_moveit_config/launch/planning_context.launch @@ -1,28 +1,25 @@ - - - - - + - - + + - + - + + - + diff --git a/ur5_e_moveit_config/launch/planning_pipeline.launch.xml b/ur5e_moveit_config/launch/planning_pipeline.launch.xml similarity index 57% rename from ur5_e_moveit_config/launch/planning_pipeline.launch.xml rename to ur5e_moveit_config/launch/planning_pipeline.launch.xml index 12211f9d8..caf1be307 100644 --- a/ur5_e_moveit_config/launch/planning_pipeline.launch.xml +++ b/ur5e_moveit_config/launch/planning_pipeline.launch.xml @@ -1,10 +1,10 @@ - + - + diff --git a/ur5e_moveit_config/launch/ros_controllers.launch b/ur5e_moveit_config/launch/ros_controllers.launch new file mode 100644 index 000000000..d71e18a0d --- /dev/null +++ b/ur5e_moveit_config/launch/ros_controllers.launch @@ -0,0 +1,11 @@ + + + + + + + + + + diff --git a/ur5_e_moveit_config/launch/run_benchmark_ompl.launch b/ur5e_moveit_config/launch/run_benchmark_ompl.launch similarity index 63% rename from ur5_e_moveit_config/launch/run_benchmark_ompl.launch rename to ur5e_moveit_config/launch/run_benchmark_ompl.launch index d37513d82..757bc9c52 100644 --- a/ur5_e_moveit_config/launch/run_benchmark_ompl.launch +++ b/ur5e_moveit_config/launch/run_benchmark_ompl.launch @@ -4,19 +4,19 @@ - + - + - - + + diff --git a/ur5_e_moveit_config/launch/sensor_manager.launch.xml b/ur5e_moveit_config/launch/sensor_manager.launch.xml similarity index 73% rename from ur5_e_moveit_config/launch/sensor_manager.launch.xml rename to ur5e_moveit_config/launch/sensor_manager.launch.xml index 172eb87be..97df2bd8f 100644 --- a/ur5_e_moveit_config/launch/sensor_manager.launch.xml +++ b/ur5e_moveit_config/launch/sensor_manager.launch.xml @@ -8,7 +8,7 @@ - - + + diff --git a/ur5_e_moveit_config/launch/setup_assistant.launch b/ur5e_moveit_config/launch/setup_assistant.launch similarity index 60% rename from ur5_e_moveit_config/launch/setup_assistant.launch rename to ur5e_moveit_config/launch/setup_assistant.launch index 3d712d563..6e0054587 100644 --- a/ur5_e_moveit_config/launch/setup_assistant.launch +++ b/ur5e_moveit_config/launch/setup_assistant.launch @@ -1,4 +1,4 @@ - + @@ -7,9 +7,9 @@ - diff --git a/ur5_e_moveit_config/launch/trajectory_execution.launch.xml b/ur5e_moveit_config/launch/trajectory_execution.launch.xml similarity index 80% rename from ur5_e_moveit_config/launch/trajectory_execution.launch.xml rename to ur5e_moveit_config/launch/trajectory_execution.launch.xml index 3513753a6..bbad585bf 100644 --- a/ur5_e_moveit_config/launch/trajectory_execution.launch.xml +++ b/ur5e_moveit_config/launch/trajectory_execution.launch.xml @@ -1,6 +1,6 @@ - + @@ -10,9 +10,9 @@ - + - - - + + + diff --git a/ur5_e_moveit_config/launch/ur5_e_moveit_controller_manager.launch.xml b/ur5e_moveit_config/launch/ur5e_moveit_controller_manager.launch.xml similarity index 78% rename from ur5_e_moveit_config/launch/ur5_e_moveit_controller_manager.launch.xml rename to ur5e_moveit_config/launch/ur5e_moveit_controller_manager.launch.xml index 6bc194070..5558a06b9 100644 --- a/ur5_e_moveit_config/launch/ur5_e_moveit_controller_manager.launch.xml +++ b/ur5e_moveit_config/launch/ur5e_moveit_controller_manager.launch.xml @@ -1,5 +1,5 @@ - + diff --git a/ur5_e_moveit_config/launch/ur5_e_moveit_planning_execution.launch b/ur5e_moveit_config/launch/ur5e_moveit_planning_execution.launch similarity index 65% rename from ur5_e_moveit_config/launch/ur5_e_moveit_planning_execution.launch rename to ur5e_moveit_config/launch/ur5e_moveit_planning_execution.launch index 148c40e4b..e73b32cc3 100644 --- a/ur5_e_moveit_config/launch/ur5_e_moveit_planning_execution.launch +++ b/ur5e_moveit_config/launch/ur5e_moveit_planning_execution.launch @@ -1,14 +1,12 @@ - - + - + - - + diff --git a/ur5_e_moveit_config/launch/ur5_e_moveit_sensor_manager.launch.xml b/ur5e_moveit_config/launch/ur5e_moveit_sensor_manager.launch.xml similarity index 100% rename from ur5_e_moveit_config/launch/ur5_e_moveit_sensor_manager.launch.xml rename to ur5e_moveit_config/launch/ur5e_moveit_sensor_manager.launch.xml diff --git a/ur5e_moveit_config/launch/ur5e_robot_moveit_controller_manager.launch.xml b/ur5e_moveit_config/launch/ur5e_robot_moveit_controller_manager.launch.xml new file mode 100644 index 000000000..58e68a4ab --- /dev/null +++ b/ur5e_moveit_config/launch/ur5e_robot_moveit_controller_manager.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + diff --git a/ur5e_moveit_config/launch/ur5e_robot_moveit_sensor_manager.launch.xml b/ur5e_moveit_config/launch/ur5e_robot_moveit_sensor_manager.launch.xml new file mode 100644 index 000000000..5d02698d7 --- /dev/null +++ b/ur5e_moveit_config/launch/ur5e_robot_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/ur5_e_moveit_config/launch/warehouse.launch b/ur5e_moveit_config/launch/warehouse.launch similarity index 67% rename from ur5_e_moveit_config/launch/warehouse.launch rename to ur5e_moveit_config/launch/warehouse.launch index 3ac1ddf6a..4ec8b7786 100644 --- a/ur5_e_moveit_config/launch/warehouse.launch +++ b/ur5e_moveit_config/launch/warehouse.launch @@ -1,13 +1,13 @@ - + - - + + - + diff --git a/ur5_e_moveit_config/launch/warehouse_settings.launch.xml b/ur5e_moveit_config/launch/warehouse_settings.launch.xml similarity index 64% rename from ur5_e_moveit_config/launch/warehouse_settings.launch.xml rename to ur5e_moveit_config/launch/warehouse_settings.launch.xml index d11aaeb21..e473b083b 100644 --- a/ur5_e_moveit_config/launch/warehouse_settings.launch.xml +++ b/ur5e_moveit_config/launch/warehouse_settings.launch.xml @@ -1,15 +1,16 @@ - - + + - - + + + diff --git a/ur5_e_moveit_config/package.xml b/ur5e_moveit_config/package.xml similarity index 94% rename from ur5_e_moveit_config/package.xml rename to ur5e_moveit_config/package.xml index f81c4cc1d..f1087d6e0 100644 --- a/ur5_e_moveit_config/package.xml +++ b/ur5e_moveit_config/package.xml @@ -1,7 +1,7 @@ - ur5_e_moveit_config + ur5e_moveit_config 1.2.5 An automatically generated package with all the configuration and launch files for using the ur5e with the MoveIt Motion Planning Framework @@ -10,7 +10,7 @@ G.A. vd. Hoorn Miguel Prada Sarasola Nadia Hammoudeh Garcia - + BSD http://moveit.ros.org/ @@ -24,10 +24,11 @@ moveit_simple_controller_manager joint_state_publisher robot_state_publisher + tf2_ros xacro ur_description roslaunch catkin - + diff --git a/ur5e_moveit_config/tests/moveit_planning_execution.xml b/ur5e_moveit_config/tests/moveit_planning_execution.xml new file mode 100644 index 000000000..34976b996 --- /dev/null +++ b/ur5e_moveit_config/tests/moveit_planning_execution.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + +