Skip to content

Commit

Permalink
Minor mods to Atlas frame names, fleshing out IRB140
Browse files Browse the repository at this point in the history
  • Loading branch information
gizatt committed Jan 27, 2015
1 parent 28494e7 commit 94070a7
Show file tree
Hide file tree
Showing 4 changed files with 47 additions and 5 deletions.
4 changes: 2 additions & 2 deletions examples/Atlas/Atlas.m
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@
% Sub in handstates for each hand
% TODO: by name?
for i=2:obj.getStateFrame().getNumFrames
atlas_state_frame = replaceFrameNum(atlas_state_frame,i,atlasFrames.HandState(obj,i,'atlasFrames.HandState'));
atlas_state_frame = replaceFrameNum(atlas_state_frame,i,atlasFrames.HandState(obj,i,'HandState'));
end
else
atlas_state_frame = atlasFrames.AtlasState(obj);
Expand All @@ -101,7 +101,7 @@
% Sub in handstates for each hand
% TODO: by name?
for i=2:obj.getInputFrame().getNumFrames
input_frame = replaceFrameNum(input_frame,i,atlasFrames.HandInput(obj,i,'atlasFrames.HandInput'));
input_frame = replaceFrameNum(input_frame,i,atlasFrames.HandInput(obj,i,'HandInput'));
end
else
input_frame = atlasFrames.AtlasInput(obj);
Expand Down
29 changes: 29 additions & 0 deletions examples/Atlas/urdf/block_hand.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<?xml version="1.0" ?>

<robot name="block_hand" xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="block_hand_box">
<inertial>
<mass value="1.0"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
</inertial>
<visual>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
<material name="gray">
<color rgba="0.5 0.5 .5 1"/>
</material>
<origin rpy="0 0 0" xyz="0 0 0"/>
</visual>
<collision group="block_hand">
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
<material name="red">
<color rgba="1.0 0.0 .0 1"/>
</material>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
</link>
</robot>
17 changes: 15 additions & 2 deletions examples/IRB140/IRB140.m
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@
obj = obj@TimeSteppingRigidBodyManipulator('',options.dt,options);
obj.initialized = 1;
obj = obj.addRobotFromURDF(urdf,options.base_offset,options.base_rpy,options);
obj.base_rpy = options.base_rpy;
obj.base_offset = options.base_offset;

if (~strcmp(options.hands, 'none'))
if (strcmp(options.hands, 'robotiq'))
Expand All @@ -37,6 +39,10 @@
% the controllers know what's up
options_hand.weld_to_link = 7;
obj = obj.addRobotFromURDF(getFullPathFromRelativePath('../Atlas/urdf/robotiq_box.urdf'), [0.1; 0.0; 0.0], [pi; 0; pi/2], options_hand);
elseif (strcmp(options.hands, 'block_hand'))
% Box with collision. Good for hitting things with...
options_hand.weld_to_link = 7;
obj = obj.addRobotFromURDF(getFullPathFromRelativePath('../Atlas/urdf/block_hand.urdf'), [0.1; 0.0; 0.0], [pi; 0; pi/2], options_hand);
else
error('unsupported hand type');
end
Expand All @@ -56,11 +62,16 @@
arm_state_frame = replaceFrameNum(arm_state_frame,1,IRB140State(obj));
% Sub in handstates for each hand
% TODO: by name?
for i=2:obj.getStateFrame().getNumFrames
for i=2:2
arm_state_frame = replaceFrameNum(arm_state_frame,i,HandState(obj,i,'HandState'));
end
else
arm_state_frame = IRB140State(obj);
arm_state_frame = getStateFrame(obj);
if (length(arm_state_frame.coordinates) > length(IRB140State(obj).coordinates))
arm_state_frame = replaceFrameNum(arm_state_frame, 1, IRB140State(obj));
else
arm_state_frame = IRB140State(obj);
end
end
tsmanip_state_frame = obj.getStateFrame();
if tsmanip_state_frame.dim>arm_state_frame.dim
Expand Down Expand Up @@ -94,5 +105,7 @@
properties (SetAccess = protected, GetAccess = public)
hands = 0; % 0, none; 1, Robotiq
initialized = 0;
base_rpy;
base_offset;
end
end
2 changes: 1 addition & 1 deletion examples/IRB140/IRB140Input.m
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
input_names = manipInputFrame.coordinates;
input_names = regexprep(input_names,'_motor',''); % remove motor suffix

obj = obj@SingletonCoordinateFrame('IRB140',length(input_names),'x',input_names);
obj = obj@SingletonCoordinateFrame('IRB140Input',length(input_names),'x',input_names);
end
end
end

0 comments on commit 94070a7

Please sign in to comment.