Skip to content

Commit f1a2d7b

Browse files
committed
Updated launch and default config file
- Updated config params - Updated launch config load directory
1 parent 1b4981c commit f1a2d7b

File tree

3 files changed

+39
-31
lines changed

3 files changed

+39
-31
lines changed

config/auto_pose.yaml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@ syropod:
1616

1717
pose_negation_phase_starts: {AR: 1, BR: 11, CR: 9, CL: 3, BL: 5, AL: 7}
1818
pose_negation_phase_ends: {AR: 3, BR: 1, CR: 11, CL: 5, BL: 7, AL: 9}
19+
negation_transition_ratio: {AR: 0, BR: 0, CR: 0, CL: 0, BL: 0, AL: 0}
1920

2021
roll_amplitudes: [-0.015, 0.015, 0.015, 0.015, -0.015, -0.015]
2122
pitch_amplitudes: [ 0.020, -0.020, 0.000, 0.020, -0.020, 0.000]
@@ -36,6 +37,7 @@ syropod:
3637

3738
pose_negation_phase_starts: {AR: 1, BR: 3, CR: 1, CL: 3, BL: 1, AL: 3}
3839
pose_negation_phase_ends: {AR: 3, BR: 1, CR: 3, CL: 1, BL: 3, AL: 1}
40+
negation_transition_ratio: {AR: 0, BR: 0, CR: 0, CL: 0, BL: 0, AL: 0}
3941

4042
roll_amplitudes: [-0.015, 0.015]
4143
pitch_amplitudes: [0.000, 0.000]
@@ -56,6 +58,7 @@ syropod:
5658

5759
pose_negation_phase_starts: {AR: 0, BR: 2, CR: 4, CL: 1, BL: 5, AL: 3}
5860
pose_negation_phase_ends: {AR: 2, BR: 4, CR: 0, CL: 3, BL: 1, AL: 5}
61+
negation_transition_ratio: {AR: 0, BR: 0, CR: 0, CL: 0, BL: 0, AL: 0}
5962

6063
roll_amplitudes: [-0.015, 0.015, -0.015, 0.015, -0.015, 0.015]
6164
pitch_amplitudes: [-0.020, 0.020, 0.000, -0.020, 0.020, 0.000]
@@ -76,6 +79,7 @@ syropod:
7679

7780
pose_negation_phase_starts: {AR: 0, BR: 2, CR: 1, CL: 0, BL: 2, AL: 1}
7881
pose_negation_phase_ends: {AR: 1, BR: 0, CR: 2, CL: 1, BL: 0, AL: 2}
82+
negation_transition_ratio: {AR: 0, BR: 0, CR: 0, CL: 0, BL: 0, AL: 0}
7983

8084
roll_amplitudes: [0.000, 0.000, 0.000]
8185
pitch_amplitudes: [0.000, 0.000, 0.000]

config/default.yaml

Lines changed: 32 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -22,30 +22,30 @@ syropod:
2222
########################################################################################################################
2323
# Model parameters
2424
syropod_type: default
25-
leg_id: [AR, BR, CR, CL, BL, AL] # leg_id_name (clockwise from front right leg)
26-
joint_id: [coxa, femur, tibia] # joint_id_name
27-
link_id: [base, coxa, femur, tibia] # link_id_name (always start with base)
28-
leg_DOF: {AL: 3, AR: 3, BL: 3, BR: 3, CL: 3, CR: 3} # leg_id_name: degrees_of_freedom (num joints)
25+
leg_id: [AR, BR, CR, CL, BL, AL] # leg_id_name (clockwise from front right leg)
26+
joint_id: [coxa, femur, tibia] # joint_id_name
27+
link_id: [base, coxa, femur, tibia] # link_id_name (always start with base)
28+
leg_DOF: {AL: 3, AR: 3, BL: 3, BR: 3, CL: 3, CR: 3} # leg_id_name: degrees_of_freedom (num joints)
2929

3030
# Joint parameters:
31-
AR_coxa_joint_parameters: {min: -0.550, max: 0.550, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
32-
AR_femur_joint_parameters: {min: -1.500, max: 1.500, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
33-
AR_tibia_joint_parameters: {min: -2.355, max: -0.100, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
34-
BR_coxa_joint_parameters: {min: -0.550, max: 0.550, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
35-
BR_femur_joint_parameters: {min: -1.500, max: 1.500, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
36-
BR_tibia_joint_parameters: {min: -2.355, max: -0.100, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
37-
CR_coxa_joint_parameters: {min: -0.550, max: 0.550, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
38-
CR_femur_joint_parameters: {min: -1.500, max: 1.500, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
39-
CR_tibia_joint_parameters: {min: -2.355, max: -0.100, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
40-
AL_coxa_joint_parameters: {min: -0.550, max: 0.550, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
41-
AL_femur_joint_parameters: {min: -1.500, max: 1.500, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
42-
AL_tibia_joint_parameters: {min: -2.355, max: -0.100, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
43-
BL_coxa_joint_parameters: {min: -0.550, max: 0.550, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
44-
BL_femur_joint_parameters: {min: -1.500, max: 1.500, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
45-
BL_tibia_joint_parameters: {min: -2.355, max: -0.100, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
46-
CL_coxa_joint_parameters: {min: -0.550, max: 0.550, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
47-
CL_femur_joint_parameters: {min: -1.500, max: 1.500, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
48-
CL_tibia_joint_parameters: {min: -2.355, max: -0.100, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
31+
AR_coxa_joint_parameters: {min: -0.550, max: 0.550, offset: 0.000, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
32+
AR_femur_joint_parameters: {min: -1.500, max: 1.500, offset: 0.000, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
33+
AR_tibia_joint_parameters: {min: -2.355, max: -0.100, offset: 0.000, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
34+
BR_coxa_joint_parameters: {min: -0.550, max: 0.550, offset: 0.000, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
35+
BR_femur_joint_parameters: {min: -1.500, max: 1.500, offset: 0.000, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
36+
BR_tibia_joint_parameters: {min: -2.355, max: -0.100, offset: 0.000, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
37+
CR_coxa_joint_parameters: {min: -0.550, max: 0.550, offset: 0.000, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
38+
CR_femur_joint_parameters: {min: -1.500, max: 1.500, offset: 0.000, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
39+
CR_tibia_joint_parameters: {min: -2.355, max: -0.100, offset: 0.000, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
40+
AL_coxa_joint_parameters: {min: -0.550, max: 0.550, offset: 0.000, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
41+
AL_femur_joint_parameters: {min: -1.500, max: 1.500, offset: 0.000, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
42+
AL_tibia_joint_parameters: {min: -2.355, max: -0.100, offset: 0.000, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
43+
BL_coxa_joint_parameters: {min: -0.550, max: 0.550, offset: 0.000, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
44+
BL_femur_joint_parameters: {min: -1.500, max: 1.500, offset: 0.000, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
45+
BL_tibia_joint_parameters: {min: -2.355, max: -0.100, offset: 0.000, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
46+
CL_coxa_joint_parameters: {min: -0.550, max: 0.550, offset: 0.000, packed: -1.571, unpacked: 0.000, max_vel: 5.000}
47+
CL_femur_joint_parameters: {min: -1.500, max: 1.500, offset: 0.000, packed: 1.900, unpacked: 0.785, max_vel: 5.000}
48+
CL_tibia_joint_parameters: {min: -2.355, max: -0.100, offset: 0.000, packed: 1.200, unpacked: -1.138, max_vel: 5.000}
4949

5050
# Link DH parameters: en.wikipedia.org/wiki/Denavit–Hartenberg_parameters
5151
AR_base_link_parameters: {d: 0.000, theta: -0.523, r: 0.050, alpha: 0.000}
@@ -79,10 +79,12 @@ syropod:
7979

8080
########################################################################################################################
8181
# Walker parameters
82-
gait_type: tripod_gait
82+
gait_type: tripod_gait
83+
body_clearance: 0.100
8384
step_frequency: {default: 1.000, min: 0.001, max: 2.000, step: 0.100} #Reconfigurable
84-
step_clearance: {default: 0.020, min: 0.010, max: 0.050, step: 0.005} #Reconfigurable
85-
body_clearance: {default: 0.100, min: 0.010, max: 0.150, step: 0.010} #Reconfigurable
85+
swing_height: {default: 0.020, min: 0.010, max: 0.050, step: 0.005} #Reconfigurable
86+
swing_width: {default: 0.000, min: -0.300, max: 0.300, step: 0.010} #Reconfigurable
87+
step_depth: {default: 0.000, min: 0.000, max: 0.000, step: 0.000} #Reconfigurable
8688
stance_span_modifier: {default: 0.000, min: -1.000, max: 1.000, step: 0.100} #Reconfigurable
8789

8890
velocity_input_mode: throttle #real
@@ -99,9 +101,11 @@ syropod:
99101
BL_stance_position: {x: 0.000, y: 0.150}
100102
AL_stance_position: {x: 0.130, y: 0.075}
101103

102-
gravity_aligned_tips: false
103-
touchdown_threshold: 0.9
104-
liftoff_threshold: 0.1
104+
overlapping_walkspaces: false
105+
force_normal_touchdown: false
106+
gravity_aligned_tips: false
107+
touchdown_threshold: 0.9
108+
liftoff_threshold: 0.1
105109

106110
########################################################################################################################
107111
# Poser parameters

launch/default_rviz.launch

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -3,9 +3,9 @@
33
<launch>
44
<include file="$(find syropod_remote)/launch/syropod_remote.launch" />
55

6-
<rosparam file="$(find default_syropod)/config/default.yaml" command="load"/>
7-
<rosparam file="$(find default_syropod)/config/gait.yaml" command="load"/>
8-
<rosparam file="$(find default_syropod)/config/auto_pose.yaml" command="load"/>
6+
<rosparam file="$(find syropod_highlevel_controller)/config/default.yaml" command="load"/>
7+
<rosparam file="$(find syropod_highlevel_controller)/config/gait.yaml" command="load"/>
8+
<rosparam file="$(find syropod_highlevel_controller)/config/auto_pose.yaml" command="load"/>
99

1010
<node name="syropod_highlevel_controller" pkg="syropod_highlevel_controller" type="syropod_highlevel_controller_node" output="screen"/>
1111

0 commit comments

Comments
 (0)