Skip to content

Commit e7ee877

Browse files
committed
Added R2019b files
1 parent a4af073 commit e7ee877

9 files changed

+24
-17
lines changed

matlab/compareTaskVsJointTraj.m

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
grid on
1414
view([45 45]);
1515
% Define IK solver
16-
ik = robotics.InverseKinematics('RigidBodyTree',gen3);
16+
ik = inverseKinematics('RigidBodyTree',gen3);
1717
ikWeights = [1 1 1 1 1 1];
1818
% Use a small sample time for this example, so the difference between joint
1919
% and task space is clear due to evaluation of IK in task space trajectory.
@@ -28,7 +28,7 @@
2828
ikInitGuess(ikInitGuess > pi) = ikInitGuess(ikInitGuess > pi) - 2*pi;
2929
ikInitGuess(ikInitGuess < -pi) = ikInitGuess(ikInitGuess < -pi) + 2*pi;
3030

31-
disp('Running task space trajectory generation and following...')
31+
disp('Running task space trajectory generation and evaluation...')
3232
tic;
3333

3434
% Trajectory generation
@@ -63,8 +63,8 @@
6363
for idx = 1:numWaypoints
6464
tgtPose = trvec2tform(waypoints(:,idx)');
6565
[config,info] = ik(eeName,tgtPose,ikWeights,ikInitGuess);
66-
ikInitGuess = config;
67-
jointWaypoints(:,idx) = config';
66+
cfgDiff = config - ikInitGuess;
67+
jointWaypoints(:,idx) = config';
6868
end
6969

7070
% Trajectory Generation

matlab/manipTrajCartesian.m

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@
1010
createWaypointData;
1111

1212
% Define IK
13-
ik = robotics.InverseKinematics('RigidBodyTree',gen3);
13+
ik = inverseKinematics('RigidBodyTree',gen3);
1414
ikWeights = [1 1 1 1 1 1];
1515
ikInitGuess = gen3.homeConfiguration;
1616

matlab/manipTrajJoint.m

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111
createWaypointData;
1212

1313
% Define IK
14-
ik = robotics.InverseKinematics('RigidBodyTree',gen3);
14+
ik = inverseKinematics('RigidBodyTree',gen3);
1515
ikWeights = [1 1 1 1 1 1];
1616
ikInitGuess = jointAnglesHome';
1717
ikInitGuess(ikInitGuess > pi) = ikInitGuess(ikInitGuess > pi) - 2*pi;
@@ -41,8 +41,6 @@
4141
tgtPose = trvec2tform(waypoints(:,idx)');
4242
end
4343
[config,info] = ik(eeName,tgtPose,ikWeights,ikInitGuess);
44-
ikInitGuess = config;
45-
4644
jointWaypoints(:,idx) = config';
4745
end
4846

matlab/manipTrajLinearRotation.m

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111
createWaypointData;
1212

1313
% Define IK
14-
ik = robotics.InverseKinematics('RigidBodyTree',gen3);
14+
ik = inverseKinematics('RigidBodyTree',gen3);
1515
ikWeights = [1 1 1 1 1 1];
1616
ikInitGuess = gen3.homeConfiguration;
1717

matlab/manipTrajTransform.m

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111
createWaypointData;
1212

1313
% Define IK
14-
ik = robotics.InverseKinematics('RigidBodyTree',gen3);
14+
ik = inverseKinematics('RigidBodyTree',gen3);
1515
ikWeights = [1 1 1 1 1 1];
1616
ikInitGuess = gen3.homeConfiguration;
1717

matlab/manipTrajTransformTimeScaling.m

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111
createWaypointData;
1212

1313
% Define IK
14-
ik = robotics.InverseKinematics('RigidBodyTree',gen3);
14+
ik = inverseKinematics('RigidBodyTree',gen3);
1515
ikWeights = [1 1 1 1 1 1];
1616
ikInitGuess = gen3.homeConfiguration;
1717

utilities/gen3.mat

89 Bytes
Binary file not shown.

utilities/importGen3Model.m

Lines changed: 15 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -3,18 +3,27 @@
33
%
44
% Copyright 2019 The MathWorks, Inc.
55

6-
% Gen3 URDF
7-
addpath(genpath('gen3_description'))
8-
gen3 = importrobot('JACO3_URDF_V11.urdf');
6+
% Load the URDF file
7+
%
8+
% NOTE: This requires you to have the kortex_description folder on
9+
% your path, which you can download from
10+
% https://github.com/Kinovarobotics/ros_kortex.git
11+
%
12+
% Then, you have to convert the gen3.xacro file to a URDF file using
13+
% the following commands in a ROS enabled terminal:
14+
% $ cd PATH/TO/ros_kortex/kortex_description/robots
15+
% $ rosrun xacro xacro --inorder -o gen3.urdf gen3.xacro
16+
addpath(genpath('kortex_description'))
17+
gen3 = importrobot('gen3.urdf');
918

1019
% Add a "dummy" gripper link
1120
gripperLength = 0.1; % Gripper length in meters
12-
gripperBody = robotics.RigidBody('Gripper');
13-
gripperJoint = robotics.Joint('GripperLink','fixed');
21+
gripperBody = rigidBody('Gripper');
22+
gripperJoint = rigidBodyJoint('GripperLink','fixed');
1423
T = rotm2tform([0 1 0;0 0 1;1 0 0]) * trvec2tform([gripperLength 0 0]);
1524
setFixedTransform(gripperJoint,T); % Move and orient the gripper
1625
gripperBody.Joint = gripperJoint;
17-
addBody(gen3,gripperBody,'EndEffector_Link');
26+
addBody(gen3,gripperBody,'end_effector_link');
1827
% Add a "dummy" mesh
1928
addVisual(gen3.Bodies{9},'Mesh','cylinder.stl', ...
2029
trvec2tform([-0.1 0 0]) * axang2tform([0 1 0 pi/2]));

utilities/waypointPublisher.mlapp

1.18 KB
Binary file not shown.

0 commit comments

Comments
 (0)