-
Notifications
You must be signed in to change notification settings - Fork 1k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
34 changed files
with
1,505 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,11 @@ | ||
moveit_setup_assistant_config: | ||
URDF: | ||
package: ur_description | ||
relative_path: urdf/ur16e.xacro | ||
xacro_args: "" | ||
SRDF: | ||
relative_path: config/ur16e.srdf | ||
CONFIG: | ||
author_name: Felix Exner | ||
author_email: [email protected] | ||
generated_timestamp: 1611154369 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,14 @@ | ||
cmake_minimum_required(VERSION 2.8.3) | ||
project(ur16e_moveit_config) | ||
|
||
find_package(catkin REQUIRED) | ||
|
||
catkin_package() | ||
|
||
if (CATKIN_ENABLE_TESTING) | ||
find_package(roslaunch REQUIRED) | ||
roslaunch_add_file_check(tests/moveit_planning_execution.xml) | ||
endif() | ||
|
||
install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) | ||
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,15 @@ | ||
controller_list: | ||
- name: fake_manipulator_controller | ||
joints: | ||
- shoulder_pan_joint | ||
- shoulder_lift_joint | ||
- elbow_joint | ||
- wrist_1_joint | ||
- wrist_2_joint | ||
- wrist_3_joint | ||
- name: fake_endeffector_controller | ||
joints: | ||
[] | ||
initial: # Define initial robot poses. | ||
- group: manipulator | ||
pose: home |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,34 @@ | ||
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed | ||
# 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: | ||
elbow_joint: | ||
has_velocity_limits: true | ||
max_velocity: 3.1415926535897931 | ||
has_acceleration_limits: false | ||
max_acceleration: 0 | ||
shoulder_lift_joint: | ||
has_velocity_limits: true | ||
max_velocity: 2.0943951023931953 | ||
has_acceleration_limits: false | ||
max_acceleration: 0 | ||
shoulder_pan_joint: | ||
has_velocity_limits: true | ||
max_velocity: 2.0943951023931953 | ||
has_acceleration_limits: false | ||
max_acceleration: 0 | ||
wrist_1_joint: | ||
has_velocity_limits: true | ||
max_velocity: 3.1415926535897931 | ||
has_acceleration_limits: false | ||
max_acceleration: 0 | ||
wrist_2_joint: | ||
has_velocity_limits: true | ||
max_velocity: 3.1415926535897931 | ||
has_acceleration_limits: false | ||
max_acceleration: 0 | ||
wrist_3_joint: | ||
has_velocity_limits: true | ||
max_velocity: 3.1415926535897931 | ||
has_acceleration_limits: false | ||
max_acceleration: 0 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,10 @@ | ||
#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 | ||
kinematics_solver_timeout: 0.005 | ||
kinematics_solver_attempts: 3 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,51 @@ | ||
<?xml version="1.0" ?> | ||
<!--This does not replace URDF, and is not an extension of URDF. | ||
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 | ||
--> | ||
<robot name="ur16e_robot"> | ||
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc--> | ||
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included--> | ||
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included--> | ||
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group--> | ||
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names--> | ||
<group name="manipulator"> | ||
<chain base_link="base_link" tip_link="tool0" /> | ||
</group> | ||
<group name="endeffector"> | ||
<link name="tool0" /> | ||
</group> | ||
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> | ||
<group_state name="home" group="manipulator"> | ||
<joint name="elbow_joint" value="0" /> | ||
<joint name="shoulder_lift_joint" value="0" /> | ||
<joint name="shoulder_pan_joint" value="0" /> | ||
<joint name="wrist_1_joint" value="0" /> | ||
<joint name="wrist_2_joint" value="0" /> | ||
<joint name="wrist_3_joint" value="0" /> | ||
</group_state> | ||
<group_state name="up" group="manipulator"> | ||
<joint name="elbow_joint" value="0" /> | ||
<joint name="shoulder_lift_joint" value="-1.5707" /> | ||
<joint name="shoulder_pan_joint" value="0" /> | ||
<joint name="wrist_1_joint" value="-1.5707" /> | ||
<joint name="wrist_2_joint" value="0" /> | ||
<joint name="wrist_3_joint" value="0" /> | ||
</group_state> | ||
<!--END EFFECTOR: Purpose: Represent information about an end effector.--> | ||
<end_effector name="moveit_ee" parent_link="tool0" group="endeffector" /> | ||
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)--> | ||
<virtual_joint name="fixed_base" type="fixed" parent_frame="world" child_link="base_link" /> | ||
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. --> | ||
<disable_collisions link1="base_link_inertia" link2="shoulder_link" reason="Adjacent" /> | ||
<disable_collisions link1="base_link_inertia" link2="upper_arm_link" reason="Never" /> | ||
<disable_collisions link1="base_link_inertia" link2="wrist_1_link" reason="Never" /> | ||
<disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent" /> | ||
<disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent" /> | ||
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" /> | ||
<disable_collisions link1="shoulder_link" link2="wrist_1_link" reason="Never" /> | ||
<disable_collisions link1="shoulder_link" link2="wrist_2_link" reason="Never" /> | ||
<disable_collisions link1="wrist_1_link" link2="wrist_2_link" reason="Adjacent" /> | ||
<disable_collisions link1="wrist_1_link" link2="wrist_3_link" reason="Never" /> | ||
<disable_collisions link1="wrist_2_link" link2="wrist_3_link" reason="Adjacent" /> | ||
</robot> |
Oops, something went wrong.