MATLAB File Help: HebiTrajectoryGenerator/executeTrajectory
HebiTrajectoryGenerator/executeTrajectory
  executeTrajectory executes a trajectory and returns when done
 
    Arguments:
 
        group     - HebiGroup containing the actuators 
        positions - [numWaypoints x numModules matrix] of 
                    positions.
 
    Parameters:
 
    'GravityVec' enables gravity compensation. It expects a
    [3 x 1] vector of the direction of gravity in the base
    frame.  Note that this direction vector is not required to
    be unit length, and that gravitational acceleration is
    assumed to be 9.81 m/s^2.
 
    'EnableDynamicsComp' [true/false] enables feeding forward
    efforts to compensate for joint accelerations. Dynamics
    compensation is turned off by default and should typically
    only be turned on if Gravity compensation is activated as
    well.
 
    'EffortOffset' sets effort offsets that get applied if
    gravity compensation or dynamics compensation is turned on.
    This can be used to account for physical features (e.g. a
    gas spring) that are not captured by other parts of the
    system.
 
    'Callback' is a user supplied function that gets called
    once per iteration. This offers a way for users to, e.g.,
    detect impacts or add impedance control. The function must
    accept 3 arguments (time,fbk,cmd) and return a
    CommandStruct. For example:
 
       % Callback with no change to the CommandStruct
        callback = @(time, fbk, cmd) cmd;
 
    Example
        % Create trajectory generator with defined kinematic
        % model for  acceleration compensation
        kin = HebiKinematics();
        kin.addBody('X5-4');
        kin.addBody('X5-Link', 'ext', 0.325, 'twist', 0);
        kin.addBody('X5-1');
        kin.addBody('X5-Link', 'ext', 0.325, 'twist', 0);
        kin.addBody('X5-1');
        trajGen = HebiTrajectoryGenerator(kin);
 
        % Create trajectory w/ automatically determined time
        positions = [0 0 0; 1 1 1];
        trajectory = trajGen.newJointMove(positions);
 
        % Simple execution
        trajGen.executeTrajectory(group, trajectory);
 
        % Execution with full options
        gravityVec = -[fbk.accelX(1) fbk.accelY(1) fbk.accelZ(1)];
        trajGen.executeTrajectory(group, trajectory, ...
            'GravityVec', gravityVec, ...
            'DynamicsComp', true, ...
            'EffortOffset', zeros(1, kin.getNumDoF), ...
            'Callback', @(time, fbk, cmd) cmd);
See also
Method Details
Access public
Sealed false
Static false