Skip to content

Commit 3405759

Browse files
authored
Merge pull request #15 from siddarth09/rusty-version-3
RUSTY version 3.0
2 parents 8d4c818 + 871bc75 commit 3405759

File tree

112 files changed

+12403
-12
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

112 files changed

+12403
-12
lines changed

Diff for: arm_config/CMakeLists.txt

+10
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
cmake_minimum_required(VERSION 3.1.3)
2+
project(arm_config)
3+
4+
find_package(catkin REQUIRED)
5+
6+
catkin_package()
7+
8+
install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
9+
PATTERN "setup_assistant.launch" EXCLUDE)
10+
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

Diff for: arm_config/config/cartesian_limits.yaml

+5
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
cartesian_limits:
2+
max_trans_vel: 1
3+
max_trans_acc: 2.25
4+
max_trans_dec: -5
5+
max_rot_vel: 1.57

Diff for: arm_config/config/chomp_planning.yaml

+18
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
planning_time_limit: 10.0
2+
max_iterations: 200
3+
max_iterations_after_collision_free: 5
4+
smoothness_cost_weight: 0.1
5+
obstacle_cost_weight: 1.0
6+
learning_rate: 0.01
7+
smoothness_cost_velocity: 0.0
8+
smoothness_cost_acceleration: 1.0
9+
smoothness_cost_jerk: 0.0
10+
ridge_factor: 0.0
11+
use_pseudo_inverse: false
12+
pseudo_inverse_ridge_factor: 1e-4
13+
joint_update_limit: 0.1
14+
collision_clearance: 0.2
15+
collision_threshold: 0.07
16+
use_stochastic_descent: true
17+
enable_failure_recovery: false
18+
max_recovery_attempts: 5

Diff for: arm_config/config/fake_controllers.yaml

+13
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
controller_list:
2+
- name: fake_rusty_arm_controller
3+
type: $(arg fake_execution_type)
4+
joints:
5+
- shoulder_pan_joint
6+
- shoulder_lift_joint
7+
- elbow_joint
8+
- wrist_1_joint
9+
- wrist_2_joint
10+
- wrist_3_joint
11+
initial: # Define initial robot poses per group
12+
- group: rusty_arm
13+
pose: home

Diff for: arm_config/config/gazebo_controllers.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
# Publish joint_states
2+
joint_state_controller:
3+
type: joint_state_controller/JointStateController
4+
publish_rate: 50

Diff for: arm_config/config/joint_limits.yaml

+40
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
2+
3+
# For beginners, we downscale velocity and acceleration limits.
4+
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
5+
default_velocity_scaling_factor: 0.1
6+
default_acceleration_scaling_factor: 0.1
7+
8+
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
9+
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
10+
joint_limits:
11+
elbow_joint:
12+
has_velocity_limits: true
13+
max_velocity: 3.15
14+
has_acceleration_limits: false
15+
max_acceleration: 0
16+
shoulder_lift_joint:
17+
has_velocity_limits: true
18+
max_velocity: 3.15
19+
has_acceleration_limits: false
20+
max_acceleration: 0
21+
shoulder_pan_joint:
22+
has_velocity_limits: true
23+
max_velocity: 3.15
24+
has_acceleration_limits: false
25+
max_acceleration: 0
26+
wrist_1_joint:
27+
has_velocity_limits: true
28+
max_velocity: 3.2
29+
has_acceleration_limits: false
30+
max_acceleration: 0
31+
wrist_2_joint:
32+
has_velocity_limits: true
33+
max_velocity: 3.2
34+
has_acceleration_limits: false
35+
max_acceleration: 0
36+
wrist_3_joint:
37+
has_velocity_limits: true
38+
max_velocity: 3.2
39+
has_acceleration_limits: false
40+
max_acceleration: 0

Diff for: arm_config/config/kinematics.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
rusty_arm:
2+
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
3+
kinematics_solver_search_resolution: 0.005
4+
kinematics_solver_timeout: 0.005

Diff for: arm_config/config/ompl_planning.yaml

+157
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,157 @@
1+
planner_configs:
2+
AnytimePathShortening:
3+
type: geometric::AnytimePathShortening
4+
shortcut: true # Attempt to shortcut all new solution paths
5+
hybridize: true # Compute hybrid solution trajectories
6+
max_hybrid_paths: 24 # Number of hybrid paths generated per iteration
7+
num_planners: 4 # The number of default planners to use for planning
8+
planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]"
9+
SBL:
10+
type: geometric::SBL
11+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
12+
EST:
13+
type: geometric::EST
14+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
15+
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
16+
LBKPIECE:
17+
type: geometric::LBKPIECE
18+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
19+
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
20+
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
21+
BKPIECE:
22+
type: geometric::BKPIECE
23+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
24+
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
25+
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
26+
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
27+
KPIECE:
28+
type: geometric::KPIECE
29+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
30+
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
31+
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
32+
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
33+
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
34+
RRT:
35+
type: geometric::RRT
36+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
37+
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
38+
RRTConnect:
39+
type: geometric::RRTConnect
40+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
41+
RRTstar:
42+
type: geometric::RRTstar
43+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
44+
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
45+
delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
46+
TRRT:
47+
type: geometric::TRRT
48+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
49+
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
50+
max_states_failed: 10 # when to start increasing temp. default: 10
51+
temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
52+
min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
53+
init_temperature: 10e-6 # initial temperature. default: 10e-6
54+
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
55+
frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
56+
k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup()
57+
PRM:
58+
type: geometric::PRM
59+
max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
60+
PRMstar:
61+
type: geometric::PRMstar
62+
FMT:
63+
type: geometric::FMT
64+
num_samples: 1000 # number of states that the planner should sample. default: 1000
65+
radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1
66+
nearest_k: 1 # use Knearest strategy. default: 1
67+
cache_cc: 1 # use collision checking cache. default: 1
68+
heuristics: 0 # activate cost to go heuristics. default: 0
69+
extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1
70+
BFMT:
71+
type: geometric::BFMT
72+
num_samples: 1000 # number of states that the planner should sample. default: 1000
73+
radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0
74+
nearest_k: 1 # use the Knearest strategy. default: 1
75+
balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1
76+
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
77+
heuristics: 1 # activates cost to go heuristics. default: 1
78+
cache_cc: 1 # use the collision checking cache. default: 1
79+
extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1
80+
PDST:
81+
type: geometric::PDST
82+
STRIDE:
83+
type: geometric::STRIDE
84+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
85+
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
86+
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
87+
degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16
88+
max_degree: 18 # max degree of a node in the GNAT. default: 12
89+
min_degree: 12 # min degree of a node in the GNAT. default: 12
90+
max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6
91+
estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0
92+
min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2
93+
BiTRRT:
94+
type: geometric::BiTRRT
95+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
96+
temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1
97+
init_temperature: 100 # initial temperature. default: 100
98+
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
99+
frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
100+
cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf
101+
LBTRRT:
102+
type: geometric::LBTRRT
103+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
104+
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
105+
epsilon: 0.4 # optimality approximation factor. default: 0.4
106+
BiEST:
107+
type: geometric::BiEST
108+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
109+
ProjEST:
110+
type: geometric::ProjEST
111+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
112+
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
113+
LazyPRM:
114+
type: geometric::LazyPRM
115+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
116+
LazyPRMstar:
117+
type: geometric::LazyPRMstar
118+
SPARS:
119+
type: geometric::SPARS
120+
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
121+
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
122+
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
123+
max_failures: 1000 # maximum consecutive failure limit. default: 1000
124+
SPARStwo:
125+
type: geometric::SPARStwo
126+
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
127+
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
128+
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
129+
max_failures: 5000 # maximum consecutive failure limit. default: 5000
130+
rusty_arm:
131+
planner_configs:
132+
- AnytimePathShortening
133+
- SBL
134+
- EST
135+
- LBKPIECE
136+
- BKPIECE
137+
- KPIECE
138+
- RRT
139+
- RRTConnect
140+
- RRTstar
141+
- TRRT
142+
- PRM
143+
- PRMstar
144+
- FMT
145+
- BFMT
146+
- PDST
147+
- STRIDE
148+
- BiTRRT
149+
- LBTRRT
150+
- BiEST
151+
- ProjEST
152+
- LazyPRM
153+
- LazyPRMstar
154+
- SPARS
155+
- SPARStwo
156+
projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint)
157+
longest_valid_segment_fraction: 0.005

Diff for: arm_config/config/ros_controllers.yaml

+12
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
controller_list:
2+
- name: "arm_controller"
3+
action_ns: follow_joint_trajectory
4+
type: FollowJointTrajectory
5+
default: true
6+
joints:
7+
- shoulder_pan_joint
8+
- shoulder_lift_joint
9+
- elbow_joint
10+
- wrist_1_joint
11+
- wrist_2_joint
12+
- wrist_3_joint

Diff for: arm_config/config/rusry.srdf

+88
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,88 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<!--This does not replace URDF, and is not an extension of URDF.
3+
This is a format for representing semantic information about the robot structure.
4+
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
5+
-->
6+
<robot name="rusry">
7+
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
8+
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
9+
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
10+
<!--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-->
11+
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
12+
<group name="rusty_arm">
13+
<joint name="shoulder_pan_joint"/>
14+
<joint name="shoulder_lift_joint"/>
15+
<joint name="elbow_joint"/>
16+
<joint name="wrist_1_joint"/>
17+
<joint name="wrist_2_joint"/>
18+
<joint name="wrist_3_joint"/>
19+
<joint name="ee_fixed_joint"/>
20+
</group>
21+
<!--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'-->
22+
<group_state name="home" group="rusty_arm">
23+
<joint name="elbow_joint" value="0"/>
24+
<joint name="shoulder_lift_joint" value="0"/>
25+
<joint name="shoulder_pan_joint" value="0"/>
26+
<joint name="wrist_1_joint" value="0"/>
27+
<joint name="wrist_2_joint" value="0"/>
28+
<joint name="wrist_3_joint" value="0"/>
29+
</group_state>
30+
<!--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. -->
31+
<disable_collisions link1="Camera_1" link2="Holder_1" reason="Never"/>
32+
<disable_collisions link1="Camera_1" link2="LW1_1" reason="Never"/>
33+
<disable_collisions link1="Camera_1" link2="LW2_1" reason="Never"/>
34+
<disable_collisions link1="Camera_1" link2="Lidar_1" reason="Never"/>
35+
<disable_collisions link1="Camera_1" link2="RW1_1" reason="Never"/>
36+
<disable_collisions link1="Camera_1" link2="RW2_1" reason="Never"/>
37+
<disable_collisions link1="Camera_1" link2="base_link" reason="Never"/>
38+
<disable_collisions link1="Camera_1" link2="rusty_base" reason="Adjacent"/>
39+
<disable_collisions link1="Camera_1" link2="shoulder_link" reason="Never"/>
40+
<disable_collisions link1="Holder_1" link2="LW1_1" reason="Never"/>
41+
<disable_collisions link1="Holder_1" link2="LW2_1" reason="Never"/>
42+
<disable_collisions link1="Holder_1" link2="Lidar_1" reason="Never"/>
43+
<disable_collisions link1="Holder_1" link2="RW1_1" reason="Never"/>
44+
<disable_collisions link1="Holder_1" link2="RW2_1" reason="Never"/>
45+
<disable_collisions link1="Holder_1" link2="base_link" reason="Default"/>
46+
<disable_collisions link1="Holder_1" link2="rusty_base" reason="Adjacent"/>
47+
<disable_collisions link1="Holder_1" link2="shoulder_link" reason="Never"/>
48+
<disable_collisions link1="LW1_1" link2="LW2_1" reason="Never"/>
49+
<disable_collisions link1="LW1_1" link2="Lidar_1" reason="Never"/>
50+
<disable_collisions link1="LW1_1" link2="RW1_1" reason="Never"/>
51+
<disable_collisions link1="LW1_1" link2="RW2_1" reason="Never"/>
52+
<disable_collisions link1="LW1_1" link2="base_link" reason="Never"/>
53+
<disable_collisions link1="LW1_1" link2="rusty_base" reason="Adjacent"/>
54+
<disable_collisions link1="LW1_1" link2="shoulder_link" reason="Never"/>
55+
<disable_collisions link1="LW2_1" link2="Lidar_1" reason="Never"/>
56+
<disable_collisions link1="LW2_1" link2="RW1_1" reason="Never"/>
57+
<disable_collisions link1="LW2_1" link2="RW2_1" reason="Never"/>
58+
<disable_collisions link1="LW2_1" link2="base_link" reason="Never"/>
59+
<disable_collisions link1="LW2_1" link2="rusty_base" reason="Adjacent"/>
60+
<disable_collisions link1="LW2_1" link2="shoulder_link" reason="Never"/>
61+
<disable_collisions link1="Lidar_1" link2="RW1_1" reason="Never"/>
62+
<disable_collisions link1="Lidar_1" link2="RW2_1" reason="Never"/>
63+
<disable_collisions link1="Lidar_1" link2="base_link" reason="Never"/>
64+
<disable_collisions link1="Lidar_1" link2="rusty_base" reason="Adjacent"/>
65+
<disable_collisions link1="Lidar_1" link2="shoulder_link" reason="Never"/>
66+
<disable_collisions link1="RW1_1" link2="RW2_1" reason="Never"/>
67+
<disable_collisions link1="RW1_1" link2="base_link" reason="Never"/>
68+
<disable_collisions link1="RW1_1" link2="rusty_base" reason="Adjacent"/>
69+
<disable_collisions link1="RW1_1" link2="shoulder_link" reason="Never"/>
70+
<disable_collisions link1="RW2_1" link2="base_link" reason="Never"/>
71+
<disable_collisions link1="RW2_1" link2="rusty_base" reason="Adjacent"/>
72+
<disable_collisions link1="RW2_1" link2="shoulder_link" reason="Never"/>
73+
<disable_collisions link1="base_link" link2="rusty_base" reason="Adjacent"/>
74+
<disable_collisions link1="base_link" link2="shoulder_link" reason="Adjacent"/>
75+
<disable_collisions link1="base_link" link2="upper_arm_link" reason="Never"/>
76+
<disable_collisions link1="base_link" link2="wrist_1_link" reason="Never"/>
77+
<disable_collisions link1="ee_link" link2="wrist_1_link" reason="Never"/>
78+
<disable_collisions link1="ee_link" link2="wrist_2_link" reason="Never"/>
79+
<disable_collisions link1="ee_link" link2="wrist_3_link" reason="Adjacent"/>
80+
<disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent"/>
81+
<disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent"/>
82+
<disable_collisions link1="rusty_base" link2="shoulder_link" reason="Never"/>
83+
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent"/>
84+
<disable_collisions link1="shoulder_link" link2="wrist_1_link" reason="Never"/>
85+
<disable_collisions link1="wrist_1_link" link2="wrist_2_link" reason="Adjacent"/>
86+
<disable_collisions link1="wrist_1_link" link2="wrist_3_link" reason="Never"/>
87+
<disable_collisions link1="wrist_2_link" link2="wrist_3_link" reason="Adjacent"/>
88+
</robot>

Diff for: arm_config/config/sensors_3d.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
sensors:
2+
[]

Diff for: arm_config/config/simple_moveit_controllers.yaml

+12
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
controller_list:
2+
- name: arm_controller
3+
action_ns: follow_joint_trajectory
4+
type: FollowJointTrajectory
5+
default: True
6+
joints:
7+
- shoulder_pan_joint
8+
- shoulder_lift_joint
9+
- elbow_joint
10+
- wrist_1_joint
11+
- wrist_2_joint
12+
- wrist_3_joint

0 commit comments

Comments
 (0)