Skip to content
Snippets Groups Projects
LoggerControl.py 49.2 KiB
Newer Older
'''This class will log 1d array in Nd matrix from device and qualisys object'''
import numpy as np
from datetime import datetime as datetime
from time import time
    def __init__(self, dt, N0_gait, joystick=None, estimator=None, loop=None, gait=None, statePlanner=None,
                 footstepPlanner=None, footTrajectoryGenerator=None, logSize=60e3, ringBuffer=False):
        self.ringBuffer = ringBuffer
        logSize = np.int(logSize)
        self.logSize = logSize
        self.i = 0

        self.dt = dt

        # Allocate the data:
        # Joystick
        self.joy_v_ref = np.zeros([logSize, 6])  # reference velocity of the joystick

        # Estimator
        self.esti_feet_status = np.zeros([logSize, 4])  # input feet status (contact or not)
        self.esti_feet_goals = np.zeros([logSize, 3, 4])  # input feet goals (desired on the ground)
        self.esti_q_filt = np.zeros([logSize, 19])  # output position
        self.esti_v_filt = np.zeros([logSize, 18])  # output velocity
        self.esti_v_secu = np.zeros([logSize, 12])  # filtered output velocity for security check

        self.esti_FK_lin_vel = np.zeros([logSize, 3])  # estimated velocity of the base with FK
        self.esti_FK_xyz = np.zeros([logSize, 3])  # estimated position of the base with FK
        self.esti_xyz_mean_feet = np.zeros([logSize, 3])  # average of feet goals
        self.esti_filt_lin_vel = np.zeros([logSize, 3])  # estimated velocity of the base before low pass filter

        self.esti_HP_x = np.zeros([logSize, 3])  # x input of the velocity complementary filter
        self.esti_HP_dx = np.zeros([logSize, 3])  # dx input of the velocity complementary filter
        self.esti_HP_alpha = np.zeros([logSize, 3])  # alpha parameter of the velocity complementary filter
        self.esti_HP_filt_x = np.zeros([logSize, 3])  # filtered output of the velocity complementary filter

        self.esti_LP_x = np.zeros([logSize, 3])  # x input of the position complementary filter
        self.esti_LP_dx = np.zeros([logSize, 3])  # dx input of the position complementary filter
        self.esti_LP_alpha = np.zeros([logSize, 3])  # alpha parameter of the position complementary filter
        self.esti_LP_filt_x = np.zeros([logSize, 3])  # filtered output of the position complementary filter

        # Loop
        self.loop_o_q = np.zeros([logSize, 18])  # position in ideal world frame (esti_q_filt + dt * loop_o_v)
        self.loop_o_v = np.zeros([logSize, 18])  # estimated velocity in world frame
        self.loop_h_v = np.zeros([logSize, 18])  # estimated velocity in horizontal frame
        self.loop_h_v_windowed = np.zeros([logSize, 6])  # estimated velocity in horizontal frame
        self.loop_t_filter = np.zeros([logSize])  # time taken by the estimator
        self.loop_t_planner = np.zeros([logSize])  # time taken by the planning
        self.loop_t_mpc = np.zeros([logSize])  # time taken by the mcp
        self.loop_t_wbc = np.zeros([logSize])  # time taken by the whole body control
        self.loop_t_loop = np.zeros([logSize])  # time taken by the whole loop (without interface)
        self.loop_t_loop_if = np.zeros([logSize])  # time taken by the whole loop (with interface)
        self.loop_q_filt_mpc = np.zeros([logSize, 6])  # position in world frame filtered by 1st order low pass
        self.loop_h_v_filt_mpc = np.zeros([logSize, 6])  # vel in base frame filtered by 1st order low pass
        self.loop_vref_filt_mpc = np.zeros([logSize, 6])  # ref vel in base frame filtered by 1st order low pass
        self.planner_gait = np.zeros([logSize, N0_gait, 4])  # Gait sequence
        self.planner_is_static = np.zeros([logSize])  # if the planner is in static mode or not

        # State planner
        if statePlanner is not None:
            self.planner_xref = np.zeros([logSize, 12, 1+statePlanner.getNSteps()])  # Reference trajectory
        if gait is not None:
            self.planner_fsteps = np.zeros([logSize, gait.getCurrentGait().shape[0], 12])  # Reference footsteps position
        self.planner_h_ref = np.zeros([logSize])  # reference height of the planner

        # Foot Trajectory Generator
        self.planner_goals = np.zeros([logSize, 3, 4])  # 3D target feet positions
        self.planner_vgoals = np.zeros([logSize, 3, 4])  # 3D target feet velocities
        self.planner_agoals = np.zeros([logSize, 3, 4])  # 3D target feet accelerations

        # Model Predictive Control
        # output vector of the MPC (next state + reference contact force)
            if loop.type_MPC == 3:
                self.mpc_x_f = np.zeros([logSize, 32, statePlanner.getNSteps()])
            else:
                self.mpc_x_f = np.zeros([logSize, 24, statePlanner.getNSteps()])
        self.mpc_solving_duration = np.zeros([logSize])

        # Whole body control
        self.wbc_P = np.zeros([logSize, 12])  # proportionnal gains of the PD+
        self.wbc_D = np.zeros([logSize, 12])  # derivative gains of the PD+
        self.wbc_q_des = np.zeros([logSize, 12])  # desired position of actuators
        self.wbc_v_des = np.zeros([logSize, 12])  # desired velocity of actuators
        self.wbc_FF = np.zeros([logSize, 12])  # gains for the feedforward torques
        self.wbc_tau_ff = np.zeros([logSize, 12])  # feedforward torques computed by the WBC
        self.wbc_ddq_IK = np.zeros([logSize, 18])  # joint accelerations computed by the IK
        self.wbc_f_ctc = np.zeros([logSize, 12])  # contact forces computed by the WBC
        self.wbc_ddq_QP = np.zeros([logSize, 18])  # joint accelerations computed by the QP
        self.wbc_feet_pos = np.zeros([logSize, 3, 4])  # current feet positions according to WBC
        self.wbc_feet_pos_target = np.zeros([logSize, 3, 4])  # current feet positions targets for WBC
        self.wbc_feet_err = np.zeros([logSize, 3, 4])  # error between feet positions and their reference
        self.wbc_feet_vel = np.zeros([logSize, 3, 4])  # current feet velocities according to WBC
        self.wbc_feet_vel_target = np.zeros([logSize, 3, 4])  # current feet velocities targets for WBC
        self.wbc_feet_acc_target = np.zeros([logSize, 3, 4])  # current feet accelerations targets for WBC

        # Timestamps
        self.tstamps = np.zeros(logSize)

    def sample(self, joystick, estimator, loop, gait, statePlanner, footstepPlanner, footTrajectoryGenerator, wbc, dT_whole):
        if (self.i >= self.logSize):
            if self.ringBuffer:
                self.i = 0
            else:
                return

        # Logging from joystick
        self.joy_v_ref[self.i] = joystick.v_ref[:, 0]

        # Logging from estimator
        self.esti_feet_status[self.i] = estimator.getFeetStatus()
        self.esti_feet_goals[self.i] = estimator.getFeetGoals()
        self.esti_q_filt[self.i] = estimator.getQFilt()
        self.esti_v_filt[self.i] = estimator.getVFilt()
        self.esti_v_secu[self.i] = estimator.getVSecu()

        self.esti_FK_lin_vel[self.i] = estimator.getFKLinVel()
        self.esti_FK_xyz[self.i] = estimator.getFKXYZ()
        self.esti_xyz_mean_feet[self.i] = estimator.getXYZMeanFeet()
        self.esti_filt_lin_vel[self.i] = estimator.getFiltLinVel()

        self.esti_HP_x[self.i] = estimator.getFilterVelX()
        self.esti_HP_dx[self.i] = estimator.getFilterVelDX()
        self.esti_HP_alpha[self.i] = estimator.getFilterVelAlpha()
        self.esti_HP_filt_x[self.i] = estimator.getFilterVelFiltX()

        self.esti_LP_x[self.i] = estimator.getFilterPosX()
        self.esti_LP_dx[self.i] = estimator.getFilterPosDX()
        self.esti_LP_alpha[self.i] = estimator.getFilterPosAlpha()
        self.esti_LP_filt_x[self.i] = estimator.getFilterPosFiltX()

        # Logging from the main loop
        self.loop_o_q[self.i] = loop.q[:, 0]
        self.loop_h_v[self.i] = loop.h_v[:, 0]
        self.loop_h_v_windowed[self.i] = loop.h_v_windowed[:, 0]
        self.loop_t_filter[self.i] = loop.t_filter
        self.loop_t_planner[self.i] = loop.t_planner
        self.loop_t_mpc[self.i] = loop.t_mpc
        self.loop_t_wbc[self.i] = loop.t_wbc
        self.loop_t_loop[self.i] = loop.t_loop
        self.loop_t_loop_if[self.i] = dT_whole
        self.loop_q_filt_mpc[self.i] = loop.q_filt_mpc[:6, 0]
        self.loop_h_v_filt_mpc[self.i] = loop.h_v_filt_mpc[:, 0]
        self.loop_vref_filt_mpc[self.i] = loop.vref_filt_mpc[:, 0]
        self.planner_xref[self.i] = statePlanner.getReferenceStates()
        self.planner_fsteps[self.i] = footstepPlanner.getFootsteps()
        self.planner_gait[self.i] = gait.getCurrentGait()
        self.planner_goals[self.i] = footTrajectoryGenerator.getFootPosition()
        self.planner_vgoals[self.i] = footTrajectoryGenerator.getFootVelocity()
        self.planner_agoals[self.i] = footTrajectoryGenerator.getFootAcceleration()
        self.planner_is_static[self.i] = gait.getIsStatic()
        self.planner_h_ref[self.i] = loop.h_ref

        # Logging from model predictive control
        self.mpc_x_f[self.i] = loop.x_f_mpc
        self.mpc_solving_duration[self.i] = loop.mpc_wrapper.t_mpc_solving_duration

        # Logging from whole body control
        self.wbc_P[self.i] = loop.result.P
        self.wbc_D[self.i] = loop.result.D
        self.wbc_q_des[self.i] = loop.result.q_des
        self.wbc_v_des[self.i] = loop.result.v_des
        self.wbc_FF[self.i] = loop.result.FF
        self.wbc_tau_ff[self.i] = loop.result.tau_ff
        self.wbc_ddq_IK[self.i] = wbc.ddq_cmd
        self.wbc_f_ctc[self.i] = wbc.f_with_delta
        self.wbc_ddq_QP[self.i] = wbc.ddq_with_delta
        self.wbc_feet_pos[self.i] = wbc.feet_pos
        self.wbc_feet_pos_target[self.i] = wbc.feet_pos_target
        self.wbc_feet_err[self.i] = wbc.feet_err
        self.wbc_feet_vel[self.i] = wbc.feet_vel
        self.wbc_feet_vel_target[self.i] = wbc.feet_vel_target
        self.wbc_feet_acc_target[self.i] = wbc.feet_acc_target

        # Logging timestamp
        self.tstamps[self.i] = time()

        self.i += 1

    def processMocap(self, N, loggerSensors):

        self.mocap_pos = np.zeros([N, 3])
        self.mocap_h_v = np.zeros([N, 3])
        self.mocap_b_w = np.zeros([N, 3])
        self.mocap_RPY = np.zeros([N, 3])
   
        for i in range(N):
            self.mocap_RPY[i] = pin.rpy.matrixToRpy(pin.Quaternion(loggerSensors.mocapOrientationQuat[i]).toRotationMatrix())

        # Robot world to Mocap initial translationa and rotation
        mTo = np.array([loggerSensors.mocapPosition[0, 0], loggerSensors.mocapPosition[0, 1], 0.02])  
        mRo = pin.rpy.rpyToMatrix(0.0, 0.0, self.mocap_RPY[0, 2])
Loading
Loading full blame...