Skip to content

Commit

Permalink
deprecate old .coordinates interface.
Browse files Browse the repository at this point in the history
  • Loading branch information
RussTedrake committed Aug 19, 2015
1 parent aa912e6 commit 310c208
Show file tree
Hide file tree
Showing 35 changed files with 70 additions and 52 deletions.
2 changes: 1 addition & 1 deletion drake/examples/Acrobot/test/paramEstSyntheticData.m
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

% Try parameter estimation without any noise
Ts = .01; breaks=getBreaks(utraj); T0 = breaks(1); Tf = breaks(end);
data = iddata(eval(xtraj,T0:Ts:Tf)',eval(utraj,T0:Ts:Tf)',Ts,'InputName',r.getInputFrame.coordinates,'OutputName',r.getOutputFrame.coordinates);
data = iddata(eval(xtraj,T0:Ts:Tf)',eval(utraj,T0:Ts:Tf)',Ts,'InputName',r.getInputFrame.getCoordinateNames(),'OutputName',r.getOutputFrame.getCoordinateNames());

estimated_parameters = parameterEstimation(r,data);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,10 +86,11 @@
terrain_map_ptr = nullPointer();
end

state_coordinates = obj.robot.getStateFrame().getCoordinateNames();
coordinate_names = struct(...
'state', {obj.robot.getStateFrame().coordinates(1:obj.robot.getNumPositions())},...
'state', {state_coordinates(1:obj.robot.getNumPositions())},...
'input', struct('robot', {atlasUtil.getHardwareJointNames(obj.robot)}, ...
'drake', {obj.robot.getInputFrame().coordinates}));
'drake', {obj.robot.getInputFrame().getCoordinateNames()}));


obj.data_mex_ptr = ...
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
else
output_frame = r.getInputFrame();
end
obj = obj@DrakeSystem(0,0,numel(input_frame.coordinates),numel(output_frame.coordinates),true,true);
obj = obj@DrakeSystem(0,0,numel(input_frame.getCoordinateNames()),numel(output_frame.getCoordinateNames()),true,true);
obj = obj.setInputFrame(input_frame);
obj = obj.setOutputFrame(output_frame);
obj.control = control;
Expand Down
3 changes: 2 additions & 1 deletion drake/examples/Atlas/+atlasFrames/AtlasCoordinates.m
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,8 @@
function obj=AtlasCoordinates(r)
typecheck(r,'TimeSteppingRigidBodyManipulator');
nq = r.getNumPositions();
obj = obj@SingletonCoordinateFrame('atlasFrames.AtlasCoordinates',nq,'x',r.getStateFrame.coordinates(1:nq));
coords = r.getStateFrame();
obj = obj@SingletonCoordinateFrame('atlasFrames.AtlasCoordinates',nq,'x',coords(1:nq));
end
end
end
2 changes: 1 addition & 1 deletion drake/examples/Atlas/+atlasFrames/AtlasInput.m
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
if (r.hand_left > 0 || r.hand_right > 0 || r.external_force ~= 0)
manipInputFrame = manipInputFrame.getFrameByNum(1);
end
input_names = manipInputFrame.coordinates;
input_names = manipInputFrame.getCoordinateNames();
input_names = regexprep(input_names,'_motor',''); % remove motor suffix

obj = obj@SingletonCoordinateFrame('atlasFrames.AtlasInput',length(input_names),'x',input_names);
Expand Down
3 changes: 2 additions & 1 deletion drake/examples/Atlas/+atlasFrames/AtlasJointConfig.m
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,8 @@
jrange = 1:nq;
end

joint_names = r.getStateFrame.coordinates(jrange);
coords = r.getStateFrame.getCoordinateNames();
joint_names = coords(jrange);
obj = obj@SingletonCoordinateFrame('NominalPositionGoal',length(jrange),'x',joint_names);
end
end
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/Atlas/+atlasFrames/AtlasPositionRef.m
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
function obj=AtlasPositionRef(r)
typecheck(r,'TimeSteppingRigidBodyManipulator');

input_names = r.getInputFrame().coordinates;
input_names = r.getInputFrame().getCoordinateNames();
input_names = regexprep(input_names,'_motor',''); % remove motor suffix

obj = obj@SingletonCoordinateFrame('atlasFrames.AtlasPositionRef',r.getNumInputs(),'x',input_names)
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/Atlas/+atlasFrames/AtlasState.m
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
if (r.hand_left > 0 || r.hand_right > 0 || r.external_force ~= 0)
manipStateFrame = manipStateFrame.getFrameByNum(1);
end
coordinates = manipStateFrame.coordinates;
coordinates = manipStateFrame.getCoordinateNames();
obj = obj@SingletonCoordinateFrame('atlasFrames.AtlasState',length(coordinates),'x',coordinates);
end
end
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/Atlas/+atlasFrames/HandInput.m
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
% our hand state is.
manipInputFrame = r.getManipulator().getInputFrame();
manipInputFrame = manipInputFrame.getFrameByNum(ind);
input_names = manipInputFrame.coordinates;
input_names = manipInputFrame.getCoordinateNames();
input_names = regexprep(input_names,'_motor',''); % remove motor suffix

obj = obj@SingletonCoordinateFrame(name,length(input_names),'x',input_names);
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/Atlas/+atlasFrames/HandState.m
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
% our hand state is.
manipStateFrame = r.getManipulator().getStateFrame();
manipStateFrame = manipStateFrame.getFrameByNum(ind);
coordinates = manipStateFrame.coordinates;
coordinates = manipStateFrame.getCoordinateNames();
obj = obj@SingletonCoordinateFrame(name,length(coordinates),'x',coordinates);
end
end
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/IRB140/HandInput.m
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
% our hand state is.
manipInputFrame = r.getManipulator().getInputFrame();
manipInputFrame = manipInputFrame.getFrameByNum(ind);
input_names = manipInputFrame.coordinates;
input_names = manipInputFrame.getCoordinateNames();
input_names = regexprep(input_names,'_motor',''); % remove motor suffix

obj = obj@SingletonCoordinateFrame(name,length(input_names),'x',input_names);
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/IRB140/HandState.m
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
% our hand state is.
manipStateFrame = r.getManipulator().getStateFrame();
manipStateFrame = manipStateFrame.getFrameByNum(ind);
coordinates = manipStateFrame.coordinates;
coordinates = manipStateFrame.getCoordinateNames();
obj = obj@SingletonCoordinateFrame(name,length(coordinates),'x',coordinates);
end
end
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/IRB140/IRB140.m
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@
end
else
arm_state_frame = getStateFrame(obj);
if (length(arm_state_frame.coordinates) > length(IRB140State(obj).coordinates))
if (length(arm_state_frame.getCoordinateNames()) > length(IRB140State(obj).getCoordinateNames()))
arm_state_frame = replaceFrameNum(arm_state_frame, 1, IRB140State(obj));
else
arm_state_frame = IRB140State(obj);
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/IRB140/IRB140Input.m
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
if (r.hands > 0)
manipInputFrame = manipInputFrame.getFrameByNum(1);
end
input_names = manipInputFrame.coordinates;
input_names = manipInputFrame.getCoordinateNames();
input_names = regexprep(input_names,'_motor',''); % remove motor suffix

obj = obj@SingletonCoordinateFrame('IRB140Input',length(input_names),'x',input_names);
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/IRB140/IRB140State.m
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
if (r.hands > 0)
manipStateFrame = manipStateFrame.getFrameByNum(1);
end
coordinates = manipStateFrame.coordinates;
coordinates = manipStateFrame.getCoordinateNames();
obj = obj@SingletonCoordinateFrame('IRB140State',length(coordinates),'x',coordinates);
end
end
Expand Down
2 changes: 1 addition & 1 deletion drake/systems/@DrakeSystem/DrakeSystem.m
Original file line number Diff line number Diff line change
Expand Up @@ -423,7 +423,7 @@ function displayStateConstraints(obj)
% to keep things clean.

con = BoundingBoxConstraint(obj.umin,obj.umax);
con = setName(con,cellfun(@(a) [a,'_limit'],obj.getInputFrame.coordinates,'UniformOutput',false));
con = setName(con,cellfun(@(a) [a,'_limit'],obj.getInputFrame.getCoordinateNames(),'UniformOutput',false));

prog = prog.addBoundingBoxConstraint(con,indices);
end
Expand Down
2 changes: 1 addition & 1 deletion drake/systems/@DrakeSystem/extractTrigPolySystem.m
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@
G=msspoly(zeros(sys.num_x)); Phi=msspoly([]); phidot=msspoly([]);
unit_circle_constraints=[];
sin_ind=false(sys.num_x); cos_ind=sin_ind; x_ind=sin_ind;
name=sys.getStateFrame.coordinates; newname={};
name=sys.getStateFrame.getCoordinateNames(); newname={};
for i=1:sys.num_x
if (deg(all_methods,s(i))>0 || deg(all_methods,c(i))>0)
xnew=[xnew;s(i);c(i)];
Expand Down
4 changes: 2 additions & 2 deletions drake/systems/@DynamicalSystem/DynamicalSystem.m
Original file line number Diff line number Diff line change
Expand Up @@ -565,7 +565,7 @@
else
sizecheck(p,obj.param_frame.dim);
end
c = obj.param_frame.coordinates;
c = obj.param_frame.getCoordinateNames();
for i=1:length(c)
obj.(c{i}) = p(i);
end
Expand All @@ -575,7 +575,7 @@
% This default getParams method attempts to get class properties of the
% system according to the coordinate names in the parameter frame.

c = obj.param_frame.coordinates;
c = obj.param_frame.getCoordinateNames();
p=zeros(obj.param_frame.dim,1);
for i=1:length(c)
p(i) = obj.(c{i});
Expand Down
5 changes: 3 additions & 2 deletions drake/systems/@LyapunovFunction/plotFunnel.m
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,9 @@
end

h=fill3(x(1,:),x(2,:),repmat(0,1,size(x,2)),options.color,'LineStyle','-','LineWidth',2);
xlabel(obj.getFrame.coordinates{options.plotdims(1)});
ylabel(obj.getFrame.coordinates{options.plotdims(2)});
coords = obj.getFrame.getCoordinateNames();
xlabel(coords{options.plotdims(1)});
ylabel(coords{options.plotdims(2)});
else
if ~isfield(options,'ts') error('you must specify the time samples for this system using options.ts'); end
ts = options.ts;
Expand Down
3 changes: 2 additions & 1 deletion drake/systems/SecondOrderSystem.m
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,8 @@
% tau = Kp*thetadesired
pdff = LinearSystem([],[],[],[],[],Kp*eye(sys.num_u));
pdff = setOutputFrame(pdff,sys.getInputFrame);
pdff = setInputFrame(pdff,CoordinateFrame('q_d',length(index),'d',{sys.getStateFrame.coordinates{index}}));
coordinates = sys.getStateFrame.getCoordinateNames();
pdff = setInputFrame(pdff,CoordinateFrame('q_d',length(index),'d',{coordinates{index}}));

if nargout>1
varargout{1} = pdff;
Expand Down
4 changes: 4 additions & 0 deletions drake/systems/frames/@CoordinateFrame/CoordinateFrame.m
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,10 @@
obj.prefix = prefix;
end

function coordinates(obj)
error('Drake:Deprecated','coordinates was a property of this class that should not have been public. please use getCoordinateName() and/or getCoordinateNames() instead.')
end

function tf = hasSamePrefix(frame1,frame2)
% useful for alarming on a possible prefix clash between two polys
tf = any(any(bsxfun(@eq,frame1.prefix,frame2.prefix')));
Expand Down
3 changes: 2 additions & 1 deletion drake/systems/plants/@Manipulator/Manipulator.m
Original file line number Diff line number Diff line change
Expand Up @@ -470,7 +470,8 @@ function num_contacts(obj)
% tau = Kp*thetadesired
pdff = LinearSystem([],[],[],[],[],Kp*eye(sys.num_u));
pdff = setOutputFrame(pdff,sys.getInputFrame);
pdff = setInputFrame(pdff,CoordinateFrame('q_d',length(index),'d',{sys.getStateFrame.coordinates{index}}));
coordinates = sys.getStateFrame.getCoordinates();
pdff = setInputFrame(pdff,CoordinateFrame('q_d',length(index),'d',{coordinates{index}}));

if nargout>1
varargout{1} = pdff;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -863,15 +863,17 @@
% name contains a specified string.
% @param str (sub)string to be searched for
% @retvall indices array of indices into state vector
indices = find(~cellfun('isempty',strfind(model.getStateFrame().coordinates(1:getNumPositions(model)),str)));
coordinates = model.getStateFrame().getCoordinateNames()
indices = find(~cellfun('isempty',strfind(coordinates(1:getNumPositions(model)),str)));
end

function indices = findVelocityIndices(model, str)
%findJointVelocityIndices Returns velocity indices in the state vector for joints whose
% name contains a specified string.
% @param str (sub)string to be searched for
% @retvall indices array of indices into state vector
indices = find(~cellfun('isempty',strfind(model.getStateFrame().coordinates((getNumPositions(model)+1):end),str)));
coordinates = model.getStateFrame().getCoordinateNames()
indices = find(~cellfun('isempty',strfind(coordinates((getNumPositions(model)+1):end),str)));
end


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@

function name_str = name(obj, t)
if(obj.isTimeValid(t))
joint_names = obj.robot.getPositionFrame().coordinates;
joint_names = obj.robot.getPositionFrame().getCoordinateNames();
name_str = cellStrCat({'Gravity compensation torque constraint on '}, ...
joint_names(obj.joint_indices), ...
{sprintf(' at time %10.4f',t)})';
Expand Down
8 changes: 4 additions & 4 deletions drake/systems/plants/constraint/test/testKinCnst.m
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@

q = randn(nq,1);
% q_aff = randn(nq_aff,1);
q_aff = [q;randn(length(robot_aff.getStateFrame.frame{2}.coordinates)/2,1)];
q_aff = [q;randn(length(robot_aff.getStateFrame.frame{2}.getCoordinateNames())/2,1)];
tspan0 = [0,1];
tspan1 = [];
t_valid = 0.5;
Expand Down Expand Up @@ -126,9 +126,9 @@
% q21_aff = randn(nq_aff,length(t2));
% q22_aff = repmat(randn(nq_aff,1),1,length(t2));
% q31_aff = repmat(randn(nq_aff,1),1,length(t3));
q21_aff = [q21;randn(length(robot_aff.getStateFrame.frame{2}.coordinates)/2,length(t2))];
q22_aff = [q22;repmat(randn(length(robot_aff.getStateFrame.frame{2}.coordinates)/2,1),1,length(t2))];
q31_aff = [q31;repmat(randn(length(robot_aff.getStateFrame.frame{2}.coordinates)/2,1),1,length(t3))];
q21_aff = [q21;randn(length(robot_aff.getStateFrame.frame{2}.getCoordinateNames())/2,length(t2))];
q22_aff = [q22;repmat(randn(length(robot_aff.getStateFrame.frame{2}.getCoordinateNames())/2,1),1,length(t2))];
q31_aff = [q31;repmat(randn(length(robot_aff.getStateFrame.frame{2}.getCoordinateNames())/2,1),1,length(t3))];
display('Check world fixed position constraint')
testKinCnst_userfun(false,false,t2,q21,q21_aff,RigidBodyConstraint.WorldFixedPositionConstraintType,robot,robot_aff,l_hand,[[0;0;1] [1;0;1]],tspan0);
kc = WorldFixedPositionConstraint(robot,l_hand,[[0;0;1] [1;0;1]],tspan0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
r = RigidBodyManipulator(urdf,options);
nq = r.getNumPositions();

l_leg_kny = find(strcmp(r.getStateFrame.coordinates,'l_leg_kny'));
r_leg_kny = find(strcmp(r.getStateFrame.coordinates,'r_leg_kny'));
l_leg_kny = find(strcmp(r.getStateFrame.getCoordinateNames(),'l_leg_kny'));
r_leg_kny = find(strcmp(r.getStateFrame.getCoordinateNames(),'r_leg_kny'));

tspan0 = [0,1];
t = [-1 0 0.2 0.4 0.7 1 2];
Expand Down
4 changes: 2 additions & 2 deletions drake/systems/plants/constraint/test/testPostureConstraint.m
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
r = RigidBodyManipulator(urdf,options);
nq = r.getNumPositions();

l_leg_kny = find(strcmp(r.getStateFrame.coordinates,'l_leg_kny'));
r_leg_kny = find(strcmp(r.getStateFrame.coordinates,'r_leg_kny'));
l_leg_kny = find(strcmp(r.getStateFrame.getCoordinateNames(),'l_leg_kny'));
r_leg_kny = find(strcmp(r.getStateFrame.getCoordinateNames(),'r_leg_kny'));

tspan0 = [0,1];
t = 0.5;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@
r = r.addRobotFromURDF('valve_task_wall.urdf',rand(3,1),pi*randn(3,1),struct('floating',false));
qsc = qsc.updateRobot(r);
nq = r.getNumPositions();
q = [q;randn(length(r.getStateFrame.frame{2}.coordinates)/2,1)];
q = [q;randn(length(r.getStateFrame.frame{2}.getCoordinateNames())/2,1)];
kinsol = doKinematics(r,q);
[c2,dc2] = qsc.eval(t,kinsol,weights);
[~,~,c_mex2,dc_mex2,lb_mex2,ub_mex2] = testQuasiStaticConstraintmex(qsc.mex_ptr,q,weights,t);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@
urdf = [getDrakePath,'/examples/Atlas/urdf/atlas_minimal_contact.urdf'];
options.floating = true;
robot = RigidBodyManipulator(urdf,options);
coords = robot.getStateFrame.coordinates(1:robot.getNumPositions);
coords = robot.getStateFrame.getCoordinateNames();
coords = coords(1:robot.getNumPositions);
l_leg_kny = find(strcmp(coords,'l_leg_kny'));
r_leg_kny = find(strcmp(coords,'r_leg_kny'));
l_leg_hpy = find(strcmp(coords,'l_leg_hpy'));
Expand Down
4 changes: 2 additions & 2 deletions drake/systems/plants/test/testApproximateIK.m
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,8 @@ function testApproximateIK()

display('Check with posture constraint');
pc = PostureConstraint(r);
l_leg_kny = find(strcmp(r.getStateFrame.coordinates,'l_leg_kny'));
r_leg_kny = find(strcmp(r.getStateFrame.coordinates,'r_leg_kny'));
l_leg_kny = find(strcmp(r.getStateFrame.getCoordinateNames(),'l_leg_kny'));
r_leg_kny = find(strcmp(r.getStateFrame.getCoordinateNames(),'r_leg_kny'));
pc = pc.setJointLimits([l_leg_kny;r_leg_kny],[0.2;0.2],[inf;inf]);
q = test_approximateIK_userfun(r,q_seed,q0,kc_com,kc_rfoot,kc_lfoot,kc_rhand,ikoption);

Expand Down
2 changes: 1 addition & 1 deletion drake/systems/plants/test/testCOM.m
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
w = warning('off','Drake:RigidBodyManipulator:ReplacedCylinder');
r = r.addRobotFromURDF('valve_task_wall.urdf',xyz,rpy,struct('floating',false));
warning(w);
nq_aff = length(r.getStateFrame.frame{2}.coordinates)/2;
nq_aff = length(r.getStateFrame.frame{2}.getCoordinateNames())/2;
q_seed_aff = zeros(nq_aff,1);
nq = r.getNumPositions();
qdot = randn(nq,1);
Expand Down
9 changes: 5 additions & 4 deletions drake/systems/plants/test/testIK.m
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,8 @@
l_hand_pts = [0;0;0];
r_hand_pts = [0;0;0];

coords = robot.getStateFrame.coordinates(1:robot.getNumPositions);
coords = robot.getStateFrame.getCoordinateNames();
coords = coords(1:robot.getNumPositions);
l_leg_kny = find(strcmp(coords,'l_leg_kny'));
r_leg_kny = find(strcmp(coords,'r_leg_kny'));
l_leg_hpy = find(strcmp(coords,'l_leg_hpy'));
Expand Down Expand Up @@ -94,8 +95,8 @@
end
end
pc_knee = PostureConstraint(robot,tspan);
l_knee_idx = find(strcmp(robot.getStateFrame.coordinates,'l_leg_kny'));
r_knee_idx = find(strcmp(robot.getStateFrame.coordinates,'r_leg_kny'));
l_knee_idx = find(strcmp(robot.getStateFrame.getCoordinateNames(),'l_leg_kny'));
r_knee_idx = find(strcmp(robot.getStateFrame.getCoordinateNames(),'r_leg_kny'));
pc_knee = pc_knee.setJointLimits([l_knee_idx;r_knee_idx],[0.2;0.2],[inf;inf]);
display('Check a single CoM constraint with a posture constraint')
q = test_IK_userfun(robot,q_seed,q_nom,kc1,pc_knee,ikoptions);
Expand Down Expand Up @@ -426,7 +427,7 @@
ikoptions = ikoptions.updateRobot(robot);
ikoptions = ikoptions.setMajorIterationsLimit(2000);
ikmexoptions = ikmexoptions.updateRobot(robot);
nq_aff = length(robot.getStateFrame.frame{2}.coordinates)/2;
nq_aff = length(robot.getStateFrame.frame{2}.getCoordinateNames())/2;
q_seed_aff = zeros(nq_aff,1);
q_nom_aff = zeros(nq_aff,1);
q = test_IK_userfun(robot,[q_seed;q_seed_aff],[q_nom;q_nom_aff],kc1,qsc,kc2l,kc2r,kc3,kc4,kc5,kc6,ikoptions);
Expand Down
3 changes: 2 additions & 1 deletion drake/systems/plants/test/testIKtraj.m
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,8 @@ function testIKtraj()


nq = r.getNumPositions();
coords = r.getStateFrame.coordinates(1:nq);
coords = r.getStateFrame.getCoordinateNames();
coords = coords(1:nq);
l_leg_kny = find(strcmp(coords,'l_leg_kny'));
r_leg_kny = find(strcmp(coords,'r_leg_kny'));
l_leg_hpy = find(strcmp(coords,'l_leg_hpy'));
Expand Down
Loading

0 comments on commit 310c208

Please sign in to comment.