Skip to content
Snippets Groups Projects
walk_parameters.yaml 6.63 KiB
Newer Older
odri's avatar
odri committed
    config_file: /home/odri/git/fanny/quadruped-reactive-walking/config/config_solo12.yaml  #  Name of the yaml file containing hardware information
odri's avatar
odri committed
    interface: enp2s0  # Name of the communication inerface (check with ifconfig)
    LOGGING: true  # Enable/disable logging during the experiment
Your Name's avatar
Your Name committed
    PLOTTING: true  # Enable/disable automatic plotting at the end of the experiment
    DEMONSTRATION: false  # Enable/disable demonstration functionalities
odri's avatar
odri committed
    SIMULATION: true  # Enable/disable PyBullet simulation or running on real robot
Fanny Risbourg's avatar
Fanny Risbourg committed
    enable_pyb_GUI: false  # Enable/disable PyBullet GUI
    envID: 0  # Identifier of the environment to choose in which one the simulation will happen
    use_flat_plane: true  # If True the ground is flat, otherwise it has bumps
odri's avatar
odri committed
    predefined_vel: true  # If we are using a predefined reference velocity (True) or a joystick (False)
Fanny Risbourg's avatar
Fanny Risbourg committed
    N_SIMULATION: 10000  # Number of simulated wbc time steps
    enable_corba_viewer: false  # Enable/disable Corba Viewer
    enable_multiprocessing: false  # Enable/disable running the MPC in another process in parallel of the main loop
Ale's avatar
Ale committed
    perfect_estimator: true  # Enable/disable perfect estimator by using data directly from PyBullet
thomascbrs's avatar
thomascbrs committed

    # q_init: [ 0.00208551,  0.97841023, -1.77335038,  0.0020868,   0.97951833, -1.77534163, 0.00208551,  0.97841023, -1.77335038,  0.0020868,   0.97951833, -1.77534163]
    # q_init: [0.0, 0.865, -1.583, 0.0, 0.865, -1.583, 0.0, 0.865, -1.583, 0.0, 0.865, -1.583] # h_com = 0.2
    # q_init: [0.0, 0.764, -1.407, 0.0, 0.76407, -1.4, 0.0, 0.76407, -1.407, 0.0, 0.764, -1.407]  # h_com = 0.218
    q_init: [0.0, 0.7, -1.4, 0.0, 0.7, -1.4, 0.0, -0.7, 1.4, 0.0, -0.7, 1.4]  # Initial articular positions
Ale's avatar
Ale committed
    dt_wbc: 0.001  # Time step of the whole body control
Ale's avatar
Ale committed
    dt_mpc: 0.015  # Time step of the model predictive control
Fanny Risbourg's avatar
Fanny Risbourg committed
    type_MPC: 3  # Which MPC solver you want to use: 0 for OSQP MPC, 1, 2, 3 for Crocoddyl MPCs
Fanny Risbourg's avatar
Fanny Risbourg committed
    save_guess: false # true to interpolate the impedance quantities between nodes of the MPC
Ale's avatar
Ale committed
    interpolate_mpc: true # true to interpolate the impedance quantities between nodes of the MPC
Fanny Risbourg's avatar
Fanny Risbourg committed
    interpolation_type: 3 # 0,1,2,3 decide which kind of interpolation is used
    # Kp_main: [0.0, 0.0, 0.0]  # Proportional gains for the PD+
    # Kd_main: [0., 0., 0.]  # Derivative gains for the PD+
#     Kff_main: 0.0  # Feedforward torques multiplier for the PD+
    Kp_main: [3, 3, 3]  # Proportional gains for the PD+
    Kd_main: [0.3, 0.3, 0.3]  # Derivative gains for the PD+
    Kff_main: 1.0  # Feedforward torques multiplier for the PD+
    gait: [8, 1, 0, 0, 1,
           8, 0, 1, 1, 0]  # Initial gait matrix
    # Parameters of Joystick
    gp_alpha_vel: 0.003  # Coefficient of the low pass filter applied to gamepad velocity
    gp_alpha_pos: 0.005  # Coefficient of the low pass filter applied to gamepad position
    t_switch: [  0,   1,   11,  12,  13,   15,   16,   117]
    v_switch: [0.0, 0.15, 0.15, 0.0, 0.0,  0.0,  0.0,  0.1, 
               0.0, 0.02, 0.0, 0.0, 0.0,  0.0,  0.0,  0.0,
               0.0, 0.0, 0.0, 0.0, 0.0,  0.0,  0.0,  0.0,
               0.0, 0.0, 0.0, 0.0, 0.0,  0.0,  0.0,  0.0,
               0.0, 0.0, 0.0, 0.0, 0.0,  0.0,  0.0,  0.0,
               0.0, 0.0, 0.0, 0.0, 0.6,  0.6,  0.0,  0.0]
    fc_v_esti: 50.0  # Cut frequency for the low pass that filters the estimated base velocity

    # Parameters of FootstepPlanner
    k_feedback: 0.03  # Value of the gain for the feedback heuristic

    # Parameters of FootTrajectoryGenerator
    max_height: 0.05  # Apex height of the swinging trajectory [m]
    lock_time: 0.04  # Target lock before the touchdown [s]
odri's avatar
odri committed
    vert_time: 0.03  # Duration during which feet move only along Z when taking off and landing
    # [0.0, 0.0, 20.0, 0.25, 0.25, 10.0, 0.05, 0.05, 0.2, 0.0, 0.0, 0.3]
    # [2.0, 2.0, 5.0, 0.25, 0.25, 1.0, 0.2, 0.2, 0.2, 0.0, 0.0, 0.3]
    osqp_w_states: [2.0, 2.0, 10.0, 0.25, 0.25, 10.0, 0.2, 0.2, 0.2, 0.0, 0.0, 0.3]  # Weights for state tracking error
    osqp_w_forces: [0.00005, 0.00005, 0.00005]  # Weights for force regularisation
    osqp_Nz_lim: 35.0  # Maximum vertical force that can be applied at contact points
    Kp_flyingfeet: 10.0  # Proportional gain for feet position tasks
    Kd_flyingfeet: 6.3  # Derivative gain for feet position tasks
    Kp_base_position: [10.0, 10.0, 10.0]  # Proportional gains for the base position task
    Kd_base_position: [6.3, 6.3, 6.3]  # Derivative gains for the base position task
    Kp_base_orientation: [10.0, 10.0, 10.0]  # Proportional gains for the base orientation task
    Kd_base_orientation: [6.3, 6.3, 6.3]  # Derivative gains for the base orientation task
    w_tasks: [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]  # Tasks weights: [feet/base, vx, vy, vz, roll+wroll, pitch+wpitch, wyaw, contacts]

    # Parameters of WBC QP problem
    Q1: 0.1  # Weights for the "delta articular accelerations" optimization variables
    Q2: 10.0  # Weights for the "delta contact forces" optimization variables
    Fz_max: 35.0  # Maximum vertical contact force [N]
pi's avatar
pi committed
    Fz_min: 0.0  # Minimal vertical contact force [N]
    enable_comp_forces: false  # Enable the use of compensation forces in the QP problem
thomascbrs's avatar
thomascbrs committed

    # Parameters fro solo3D simulation
Fanny Risbourg's avatar
Fanny Risbourg committed
    solo3D: false  # Activation of the 3D environment, and corresponding planner blocks
    enable_multiprocessing_mip: true  # Enable/disable running the MIP in another process in parallel of the main loop
    environment_URDF: "/short_bricks/short_bricks.urdf"
    environment_heightmap: "/short_bricks/short_bricks.bin"
    heightmap_fit_length: 0.2 # Length of half the heightmap fit in a direction
    heightmap_fit_size: 5 # Number of points on each axis in the heightmap fit
    number_steps: 3 # Number of steps to ptimize with the MIP
    max_velocity: [0.4, 0.4, 0.1] # Maximum velocity of the base
    use_bezier: false # Use Bezier to plan trajectories, otherwise use simple 6d polynomial curve.
    use_sl1m: true # Use SL1M to select the surfaces, otherwise use Raibert heuristic projection in 2D.
    use_heuristic: true # Use heuristic as SL1M cost.
Fanny Risbourg's avatar
Fanny Risbourg committed
    bezier_x_margin_max: 0.06 # margin inside convex surfaces [m].
    bezier_t_margin: 0.3 # 100*t_margin_% of the curve around critical point. range: [0, 1]
    bezier_z_margin: 0.06 # 100*z_margin_% of the curve after the critical point. range: [0, 1]
    bezier_N_sample: 8 # Number of sample in the least square optimisation for Bezier coeffs
    bezier_N_sample_ineq: 10 # Number of sample while browsing the curve
    bezier_degree: 7 # Degree of the Bezier curve