Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

added walking configuration files for ergoCubGazeboV1 #134

Merged
merged 1 commit into from
Feb 10, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
controllerHorizon 2

stateWeightTriplets ((0,0,7500), (1,1,7500))
inputWeightTriplets ((0,0,9000000), (1,1,9000000))

#Foot Dimensions x_min x_max y_min y_max
foot_size ((-0.12 0.12), (-0.05 0.05))
initial_zmp_position (0.0 0.0)

convex_hull_tolerance 0.05
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
kDCM 1.2
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
# name of the left and right feet wrench ports
left_foot_wrench_input_port_name ("/left_foot_front/cartesianEndEffectorWrench:i",
"/left_foot_rear/cartesianEndEffectorWrench:i")
left_foot_wrench_output_port_name ("/wholeBodyDynamics/left_foot_front/cartesianEndEffectorWrench:o",
"/wholeBodyDynamics/left_foot_rear/cartesianEndEffectorWrench:o")

right_foot_wrench_input_port_name ("/right_foot_front/cartesianEndEffectorWrench:i",
"/right_foot_rear/cartesianEndEffectorWrench:i")
right_foot_wrench_output_port_name ("/wholeBodyDynamics/right_foot_front/cartesianEndEffectorWrench:o",
"/wholeBodyDynamics/right_foot_rear/cartesianEndEffectorWrench:o")
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
#the x axis pointing forward the z axis pointing upward and the y concludes a right-handed frame
left_foot_frame l_sole
right_foot_frame r_sole

# hand frames
left_hand_frame l_hand_palm
right_hand_frame r_hand_palm

head_frame head

root_frame root_link
torso_frame neck_2

# filters
# if it is equal to 0 the low pass filters are not used
use_filters 0
#Hz
cut_frequency 10.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
[ELLIPSE_METHOD_SETTINGS]
#This factor affects the reference of the unicycle. It allows switching between the specified ellipse and a smaller one to
#take into account the robot dimensions. If 0, it always considers only the specified ellipse. If greater than zero, the reference
#to the unicycle will be projected in a smaller ellipse as soon as the unicycle is no more perpendicular to the ellipse.
#Greater values make this behavior more sensitive.
conservative_factor 2.0

#This offset is subtracted from the semi_minor_axis and semi_major_axis to obtain the inner ellipse
inner_ellipse_offset 0.5

[ELLIPSE_MANAGER_SETTINGS]
port_name freeSpaceEllipse:in

use_initial_ellipse 0

[INITIAL_ELLIPSE]

#Axis along the x direction
semi_major_axis 1.0

#Axis along the y direction
semi_minor_axis 1.0

#Rotation around the z axis
angle 0.0

#x coordinate of the center
center_x 0.1

#y coordinate of the center
center_y 0.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
# PID handling file

# All the following phases are those of the left foot. In a specific phase, a joint will have the PIDs specified in the corresponding section. If not, the default will be used (if specified, the original PID otherwise).

# Possible phases: SWING_LEFT, SWING_RIGHT, SWITCH

# Each group, except DEFAULT, contains:
# -the field activationPhase with one of the possible phases defined above,
# -the field activationOffset which specified the time advance/delay (if the sign is + it will be a delay) wrt the begin of the phase (OPTIONAL, default 0.0)
# -the field smoothingTime which defines the smoothing time with which the PIDs will be changed (OPTIONAL, default 1.0)

# if 0 only the default group will be taken into consideration
useGainScheduling 0

[DEFAULT]
#NAME P I D
torso_pitch 40.0 0.35 0.35
torso_roll 40.0 0.35 0.35
torso_yaw 40.0 0.35 0.35
l_knee 40.0 0.35 0.35
r_knee 40.0 0.35 0.35
l_ankle_pitch 40.0 0.35 0.35
r_ankle_pitch 40.0 0.35 0.35
l_ankle_roll 40.0 0.35 0.35
r_ankle_roll 40.0 0.35 0.35
l_hip_pitch 40.0 0.35 0.35
r_hip_pitch 40.0 0.35 0.35
l_hip_roll 40.0 0.35 0.35
r_hip_roll 40.0 0.35 0.35
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
##Timings
plannerHorizon 10.0

##Unicycle Related Quantities
unicycleGain 10.0
referencePosition (0.1 0.0)
timeWeight 2.5
positionWeight 1.0
slowWhenTurningGain 5.0
slowWhenBackwardFactor 1.0

##Bounds
#Step length
maxStepLength 0.21
minStepLength 0.05
#Width
minWidth 0.12
#Angle Variations in DEGREES
#maxAngleVariation 12.0
maxAngleVariation 22.0
minAngleVariation 8.0
#Timings
maxStepDuration 1.3
minStepDuration 1.1

##Nominal Values
#Width
nominalWidth 0.16
#Height
stepHeight 0.02
stepLandingVelocity 0.0
footApexTime 0.7
comHeightDelta 0.0
#Timings
nominalDuration 1.2
lastStepSwitchTime 0.8
switchOverSwingRatio 1.0

#ZMP Delta
leftZMPDelta (-0.015 -0.01)
rightZMPDelta (-0.015 0.01)

#Feet cartesian offset on the yaw
leftYawDeltaInDeg 0.0
rightYawDeltaInDeg 0.0

# Last Step DCM Offset
# If it is 0.5 the final DCM will be in the middle of the two footsteps;
# If it is 0 the DCM position coincides with the stance foot ZMP;
# If it is 1 the DCM position coincides with the next foot ZMP position.
lastStepDCMOffset 0.25

#MergePoint
mergePointRatio 0.4

# pitch delta
pitchDelta 0.0

##Should be the first step with the left foot?
swingLeft 1
startAlwaysSameFoot 1

##Remove this line if you don't want to use the minimum jerk trajectory in feet interpolation
# useMinimumJerkFootTrajectory 1
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
dataLoggerOutputPort_name /logger/data:o
dataLoggerRpcOutputPort_name /logger/rpc:o

dataLoggerInputPort_name /yarp-robot-logger/exogenous_signals/walking:i
dataLoggerRpcInputPort_name /logger/rpc:i
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
# remove the following line if you do not want the gain scheduling
useGainScheduling 1

smoothingTime 0.05

# if the gain scheduling is off only k*_walking parameters are used
kZMP_walking 1.0
# kZMP_stance 1.0
kCoM_walking 3.0

kZMP_stance 1.0
# kZMP_stance 1.0
kCoM_stance 3.0

# old parameters
#kZMP 2.0 low velocity reactive
#kZMP 1.9 low velocity MPC

#kCoM 10.0 low velocity reactive
#kCoM 8.0 low velocity MPC
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
#The left_foot_frame is supposed to have the same orientation of the Inertia frame, which have the z axis pointing upwards,
#the x axis pointing forward and and the y concludes a right-handed frame
left_foot_frame l_sole
right_foot_frame r_sole

# #Remove the following line in order not to consider the
# #additional frame
additional_frame chest

# #The additional rotation is defined (by rows) in the Inertia frame.
#Remove the following line to keep the identity as additional rotation
additional_rotation ((1.0 0.0 0.0),(0.0 1.0 0.0),(0.0 0.0 1.0))

# solver paramenters
solver-verbosity 1
solver_name ma27
max-cpu-time 20


# joints_list "torso_pitch", "torso_roll", "torso_yaw",
# "l_shoulder_pitch", "l_shoulder_roll", "l_shoulder_yaw", "l_elbow",
# "r_shoulder_pitch", "r_shoulder_roll", "r_shoulder_yaw", "r_elbow",
# "l_hip_pitch", "l_hip_roll", "l_hip_yaw", "l_knee", "l_ankle_pitch", "l_ankle_roll",
# "r_hip_pitch", "r_hip_roll", "r_hip_yaw", "r_knee", "r_ankle_pitch", "r_ankle_roll"


#DEGREES
jointRegularization (7, 0.12, -0.01,
-3.7, 20.0, -13.0, 40.769,
-3.7, 20.0, -13.0, 40.769,
5.76, 1.61, -0.31, -31.64, -20.52, -1.52,
5.76, 1.61, -0.31, -31.64, -20.52, -1.52)

#jointRegularization (0, 15, 0, 0, -29.794, 29.97, 0.00, 44.977, -29.794, 29.97, 0.00, 44.977, 5.082, 0.406, -0.131, -45.249, -26.454, -0.351, 5.082, 0.406, -0.131, -45.249, -26.454, -0.351)
#jointRegularization (15, 0, 0, 5.082, 0.406, -0.131, -45.249, -26.454, -0.351, 5.082, 0.406, -0.131, -45.249, -26.454, -0.351)
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
# CoM
use_com_as_constraint 1
# comWeightTriplets ((0,0,100), (1,1,100), (2,2,100))


# weight matrices related to the neck
neck_weight 5.0
additional_rotation ((1.0 0.0 0.0),(0.0 1.0 0.0),(0.0 0.0 1.0))

# Joint regularization term
joint_regularization (7, 0.12, -0.01,
-3.7, 20.0, -13.0, 40.769,
-3.7, 20.0, -13.0, 40.769,
5.76, 1.61, -0.31, -31.64, -20.52, -1.52,
5.76, 1.61, -0.31, -31.64, -20.52, -1.52)

joint_regularization_weights (1.0, 1.0, 1.0,
2.0, 2.0, 2.0, 2.0,
2.0, 2.0, 2.0, 2.0,
1.0, 1.0, 1.0, 1.0, 1.0, 1.0,
1.0, 1.0, 1.0, 1.0, 1.0, 1.0)

joint_regularization_gains (5.0, 5.0, 5.0,
5.0, 5.0, 5.0, 5.0,
5.0, 5.0, 5.0, 5.0,
5.0, 5.0, 5.0, 5.0, 5.0, 5.0,
5.0, 5.0, 5.0, 5.0, 5.0, 5.0)

# Gains
k_posCom 1.0
k_posFoot 7.0
k_attFoot 5.0
k_neck 5.0

# joint limits
k_joint_limit_lower_bound 1.0
k_joint_limit_upper_bound 1.0

# use_joint_limits_constraint 1
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
robot ergocubSim

joints_list ("torso_pitch", "torso_roll", "torso_yaw",
"l_shoulder_pitch", "l_shoulder_roll", "l_shoulder_yaw", "l_elbow",
"r_shoulder_pitch", "r_shoulder_roll", "r_shoulder_yaw", "r_elbow",
"l_hip_pitch", "l_hip_roll", "l_hip_yaw", "l_knee", "l_ankle_pitch", "l_ankle_roll",
"r_hip_pitch", "r_hip_roll", "r_hip_yaw", "r_knee", "r_ankle_pitch", "r_ankle_roll")

remote_control_boards ("torso", "left_arm", "right_arm", "left_leg", "right_leg")

# filters
# if use_*_filter is equal to 0 the low pass filters are not used
use_joint_velocity_filter 0
joint_velocity_cut_frequency 10.0

use_wrench_filter 0
wrench_cut_frequency 10.0


# if true the joint is in stiff mode if false the joint is in compliant mode
joint_is_stiff_mode (true, true, true,
true, true, true, true,
true, true, true, true,
true, true, true, true, true, true,
true, true, true, true, true, true)

# if true a good joint traking is considered mandatory
good_tracking_required (true, true, true,
true, true, true, true,
true, true, true, true,
true, true, true, true, true, true,
true, true, true, true, true, true)
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
# Remove this line if you don't want to use the MPC
# use_mpc 1

# Remove this line if you don't want to use the QP-IK
use_QP-IK 1

# Remove this line if you don't want to use osqp to
# solve QP-IK. In this case qpOASES will be used
use_osqp 1

# remove this line if you don't want to save data of the experiment
dump_data 0

# Limit on the maximum initial velocity. This avoids the robot to jump at startup
max_initial_com_vel 0.5

# Tolerance radius to consider the measured ZMP constant.
constant_ZMP_tolerance 0.0001

# Consecutive times in which the ZMP remains constant. If this limit is reached, the module stops. Use a negative value to disable.
constant_ZMP_counter -1

# Minimum force to consider the ZMP valid.
minimum_normal_force_ZMP 1.0

# Limit to consider the ZMP valid
# |x| |y|
maximum_local_zmp (0.4, 0.3)

# If set to true, the desired ZMP is used directly in the COM/ZMP controller
skip_dcm_controller 0

# general parameters
[GENERAL]
name walking-coordinator
# height of the com
com_height 0.72
# sampling time
sampling_time 0.01
# Specify the frame to use to control the robot height. Currently, we support only the following options: com, root_link
height_reference_frame com

# include robot control parameters
[include ROBOT_CONTROL "./dcm_walking/joypad_control/robotControl.ini"]

# include trajectory planner parameters
[include TRAJECTORY_PLANNER "./dcm_walking/common/plannerParams.ini"]

# include free space ellipsoid manager parameters
[include FREE_SPACE_ELLIPSE_MANAGER "./dcm_walking/common/freeSpaceEllipseParams.ini"]

# include MPC parameters
[include DCM_MPC_CONTROLLER "./dcm_walking/common/controllerParams.ini"]

# include MPC parameters
[include DCM_REACTIVE_CONTROLLER "./dcm_walking/common/dcmReactiveControllerParams.ini"]

# include MPC parameters
[include ZMP_CONTROLLER "./dcm_walking/common/zmpControllerParams.ini"]

# include inverse kinematcs parameters
[include INVERSE_KINEMATICS_SOLVER "./dcm_walking/joypad_control/inverseKinematics.ini"]

# include qp inverse kinematcs parameters
[include INVERSE_KINEMATICS_QP_SOLVER "./dcm_walking/joypad_control/qpInverseKinematics.ini"]

# include inverse kinematcs parameters
[include FORWARD_KINEMATICS_SOLVER "./dcm_walking/common/forwardKinematics.ini"]

# include FT sensors parameters
[include FT_SENSORS "./dcm_walking/common/forceTorqueSensors.ini"]

# include Logger parameters
[include WALKING_LOGGER "./dcm_walking/common/walkingLogger.ini"]

# include lower PID parameters
[include PID "./dcm_walking/common/pidParams.ini"]