MATLAB File Help: HebiTrajectoryGenerator/newJointMove
HebiTrajectoryGenerator/newJointMove
  newJointMove creates a trajectory through joint waypoints
 
  Arguments:
 
    Positions     - [numWaypoints x numJoints] matrix
 
  Parameters:
 
    Note that some trajectory algorithms may not support all of
    the following parameters.
 
    'Duration' [s] is a scalar that sets the desired duration
    at which the trajectory should be completed. This
    overwrites any automatically determined duration, so the
    resulting trajectory may not be technically feasible.
 
    'Time' [s] is a vector of time constraints for each
    waypoint. This overwrites any automatically determined
    duration, so the resulting trajectory may not be
    technically feasible. The vector needs to start at zero, 
    be monotonically increasing, and not contain nan or inf.
 
    'Velocities' [rad/s] is a matrix of velocity constraints
    for each waypoint. Unspecified values ('nan') will be
    determined automatically. If velocities are not specified,
    the default assumes zero start and end conditions.
    For a waypoint for 4 joints over 5 waypoints this would be
    equivalent to the following
        
        defaultVelocities = [
             0   0   0   0 
            nan nan nan nan
            nan nan nan nan
            nan nan nan nan
             0   0   0   0 ];
    
    'Accelerations' [rad/s^2] is a matrix of acceleration 
    constraints for each waypoint. Unspecified values ('nan') 
    will be determined automatically. If accelerations are not 
    specified, the default is the same as for velocities, i.e.,
    zero start and end conditions.
 
    Example:
        % Setup trajectory generator for a single joint
        kin = HebiKinematics();
        kin.addBody('X5-1');
        velocityLimit = kin.getJointInfo().velocityLimit;
        trajGen = HebiTrajectoryGenerator(velocityLimit);
 
    Example:
        % Create trajectory with automated time scaling, with
        % specified settings to slow down from defaults.
        trajGen.setMinDuration(1.0);  
        trajGen.setSpeedFactor(0.5);  
        positions = rand(10, kin.getNumDoF());
        trajectory = trajGen.newJointMove(positions);
 
    Example:
        % Create a trajectory that goes through 10 waypoints
        % in 4 seconds.
        positions = rand(10, kin.getNumDoF());
        trajectory = trajGen.newJointMove(positions, ...
            'Duration', 4.0);
 
    Example:
        % Visualize the trajectory
        positions = rand(10, kin.getNumDoF());
        trajectory = trajGen.newJointMove(positions);
        HebiUtils.plotTrajectory(trajectory);
 
    Example:
        % Create trajectory
        positions = rand(10, kin.getNumDoF());
        trajectory = trajGen.newJointMove(positions);
 
        % Manually execute position/velocity/effort trajectory
        cmd = CommandStruct();
        t0 = tic();
        t = toc(t0);
        while t < trajectory.getDuration()
            fbk = group.getNextFeedback();
 
            % get state at current time interval
            t = toc(t0);
            [pos, vel, accel] = trajectory.getState(t);
 
            % compensate for gravity
            gravityVec = -[fbk.accelX(1) fbk.accelY(1) fbk.accelZ(1)];
            gravCompEffort = kin.getGravCompEfforts(fbk.position, gravityVec);
 
            % compensate for accelerations
            accelCompEffort = kin.getDynamicCompEfforts(...
                fbk.position, ... % used for jacobian
                pos, vel, accel);
 
            % send to hardware
            cmd.position = pos;
            cmd.velocity = vel;
            cmd.effort = gravCompEffort + accelCompEffort;
            group.send(cmd);
 
       end
 
    Example:
        % Setup trajectory generator for a single joint
        kin = HebiKinematics();
        kin.addBody('X5-1');
        velocityLimit = kin.getJointInfo().velocityLimit;
        trajGen = HebiTrajectoryGenerator(velocityLimit);
 
        % Create single joint trajectory with constraints
        positions     = [ 0  1   3   3   1   0 ]';
        velocities    = [ 0 nan  0   0  nan  0 ]';
        accelerations = [ 0 nan nan nan nan  0 ]';
        waypointTimes = [ 0  1   2   3   4   5 ]';
 
        trajectory = trajGen.newJointMove( positions, ...
            'Velocities', velocities, ...
            'Accelerations', accelerations, ...
            'Time', waypointTimes );
 
        % Visualize the position/velocity/accelerations.
        HebiUtils.plotTrajectory(trajectory);
See also
Method Details
Access public
Sealed false
Static false