Skip to content

Commit

Permalink
Commit of R2018b files
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass committed Oct 15, 2019
1 parent c1793c2 commit 15740f7
Show file tree
Hide file tree
Showing 9 changed files with 9 additions and 106 deletions.
Binary file modified Libraries/OpenManipulatorLib.slx
Binary file not shown.
Binary file modified Models/openManipulatorBallTracking.slx
Binary file not shown.
Binary file modified Models/openManipulatorWaypointTracking.slx
Binary file not shown.
8 changes: 3 additions & 5 deletions ScriptsFunctions/Kinematics/createRigidBodyTree.m
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,7 @@
% Add gravity
gravityVec = [0 0 -9.80665];
robot.Gravity = gravityVec;

% Add inertial properties
setRobotInertialProperties;


% Add another massless coordinate frame for the end effector
eeOffset = 0.12;
eeBody = robotics.RigidBody('end_effector');
Expand All @@ -25,7 +22,8 @@

% If this fails, load the preloaded rigid body tree
catch
load openManipulatorDescription robot;
warning('Error importing URDF file. Loading presaved object.');
load openManipulatorDescription robot
end

% Return its home configuration
Expand Down
Binary file modified ScriptsFunctions/Kinematics/openManipulatorDescription.mat
Binary file not shown.
9 changes: 1 addition & 8 deletions ScriptsFunctions/Kinematics/openManipulatorIK.m
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
clc

addpath(genpath(strcat(pwd,'\Dependencies')))
robot = importrobot('open_manipulator.urdf');
robot = createRigidBodyTree;
axes = show(robot);
axes.CameraPositionMode = 'auto';

Expand All @@ -29,13 +29,6 @@
fnplt(trajectory,'r',2);

%% Perform Inverse Kinematics for a point in space

% Add end effector frame, offset from the grip link frame
eeOffset = 0.12;
eeBody = robotics.RigidBody('end_effector');
setFixedTransform(eeBody.Joint,trvec2tform([eeOffset 0 0]));
addBody(robot,eeBody,'link5');

ik = robotics.InverseKinematics('RigidBodyTree',robot);
weights = [0.1 0.1 0 1 1 1];
initialguess = robot.homeConfiguration;
Expand Down
43 changes: 0 additions & 43 deletions ScriptsFunctions/Kinematics/setRobotInertialProperties.m

This file was deleted.

46 changes: 0 additions & 46 deletions ScriptsFunctions/Kinematics/simInvKin.m

This file was deleted.

9 changes: 5 additions & 4 deletions ScriptsFunctions/Utilities/checkDependencies.m
Original file line number Diff line number Diff line change
Expand Up @@ -52,15 +52,16 @@
urdfFolder = fileparts(xacroFile);
urdfFile = fullfile(urdfFolder,'open_manipulator.urdf');
filetext = fileread('open_manipulator.urdf.xacro');
% String replace all the joint angle limit expressions with numeric values
[startIdx,endIdx] = regexp(filetext,'\${(-)?pi*\S*}');
% String replace all the expressions with numeric values
searchExpression = '\${[^}]*\d+[^}]*}'; % Starts with $ and has text (with at least one number) between { }
[startIdx,endIdx] = regexp(filetext,searchExpression);
while ~isempty(startIdx)
token = filetext(startIdx(1):endIdx(1));
numericVal = eval(token(3:end-1));
filetext = strrep(filetext,token,num2str(numericVal));
[startIdx,endIdx] = regexp(filetext,'\${(-)?pi*\S*}');
[startIdx,endIdx] = regexp(filetext,searchExpression);
end
% Write the URDf file with the new text
% Write the URDF file with the new text
file = fopen(urdfFile,'w');
fwrite(file,filetext);
fclose(file);
Expand Down

0 comments on commit 15740f7

Please sign in to comment.