Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
P
Panda Moveit Config
Manage
Activity
Members
Labels
Plan
Issues
0
Issue boards
Milestones
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Package Registry
Model registry
Operate
Environments
Terraform modules
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Guillaume Duret
Panda Moveit Config
Commits
e7a0f470
Commit
e7a0f470
authored
3 years ago
by
Thore Goll
Committed by
Robert Haschke
3 years ago
Browse files
Options
Downloads
Patches
Plain Diff
Use STOMP config for both arm groups
parent
e60dc0b6
No related branches found
No related tags found
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
config/stomp_planning.yaml
+37
-40
37 additions, 40 deletions
config/stomp_planning.yaml
launch/stomp_planning_pipeline.launch.xml
+10
-1
10 additions, 1 deletion
launch/stomp_planning_pipeline.launch.xml
with
47 additions
and
41 deletions
config/stomp_planning.yaml
+
37
−
40
View file @
e7a0f470
stomp/panda_arm
:
group_name
:
panda_arm
optimization
:
num_timesteps
:
60
num_iterations
:
40
num_iterations_after_valid
:
0
num_rollouts
:
30
max_rollouts
:
30
initialization_method
:
1
#[1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST]
control_cost_weight
:
0.0
task
:
noise_generator
:
-
class
:
stomp_moveit/NormalDistributionSampling
stddev
:
[
0.05
,
0.8
,
1.0
,
0.8
,
0.4
,
0.4
,
0.4
]
cost_functions
:
-
class
:
stomp_moveit/CollisionCheck
collision_penalty
:
1.0
cost_weight
:
1.0
kernel_window_percentage
:
0.2
longest_valid_joint_move
:
0.05
noisy_filters
:
-
class
:
stomp_moveit/JointLimits
lock_start
:
True
lock_goal
:
True
-
class
:
stomp_moveit/MultiTrajectoryVisualization
line_width
:
0.02
rgb
:
[
255
,
255
,
0
]
marker_array_topic
:
stomp_trajectories
marker_namespace
:
noisy
update_filters
:
-
class
:
stomp_moveit/PolynomialSmoother
poly_order
:
6
-
class
:
stomp_moveit/TrajectoryVisualization
line_width
:
0.05
rgb
:
[
0
,
191
,
255
]
error_rgb
:
[
255
,
0
,
0
]
publish_intermediate
:
True
marker_topic
:
stomp_trajectory
marker_namespace
:
optimized
\ No newline at end of file
optimization
:
num_timesteps
:
60
num_iterations
:
40
num_iterations_after_valid
:
0
num_rollouts
:
30
max_rollouts
:
30
initialization_method
:
1
#[1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST]
control_cost_weight
:
0.0
task
:
noise_generator
:
-
class
:
stomp_moveit/NormalDistributionSampling
stddev
:
[
0.05
,
0.8
,
1.0
,
0.8
,
0.4
,
0.4
,
0.4
]
cost_functions
:
-
class
:
stomp_moveit/CollisionCheck
collision_penalty
:
1.0
cost_weight
:
1.0
kernel_window_percentage
:
0.2
longest_valid_joint_move
:
0.05
noisy_filters
:
-
class
:
stomp_moveit/JointLimits
lock_start
:
True
lock_goal
:
True
-
class
:
stomp_moveit/MultiTrajectoryVisualization
line_width
:
0.02
rgb
:
[
255
,
255
,
0
]
marker_array_topic
:
stomp_trajectories
marker_namespace
:
noisy
update_filters
:
-
class
:
stomp_moveit/PolynomialSmoother
poly_order
:
6
-
class
:
stomp_moveit/TrajectoryVisualization
line_width
:
0.05
rgb
:
[
0
,
191
,
255
]
error_rgb
:
[
255
,
0
,
0
]
publish_intermediate
:
True
marker_topic
:
stomp_trajectory
marker_namespace
:
optimized
This diff is collapsed.
Click to expand it.
launch/stomp_planning_pipeline.launch.xml
+
10
−
1
View file @
e7a0f470
...
...
@@ -21,5 +21,14 @@
<!-- Add MoveGroup capabilities specific to this pipeline -->
<!-- <param name="capabilities" value="" /> -->
<rosparam
command=
"load"
file=
"$(find panda_moveit_config)/config/stomp_planning.yaml"
/>
<!-- Load parameters for both groups, panda_arm and manipulator -->
<group
ns=
"panda_arm"
>
<rosparam
command=
"load"
file=
"$(find panda_moveit_config)/config/stomp_planning.yaml"
/>
<param
name=
"group_name"
value=
"panda_arm"
/>
</group>
<group
ns=
"manipulator"
>
<rosparam
command=
"load"
file=
"$(find panda_moveit_config)/config/stomp_planning.yaml"
/>
<param
name=
"group_name"
value=
"manipulator"
/>
</group>
</launch>
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment