Skip to content

Commit 350c75b

Browse files
authored
Merge pull request #7 from PickNikRobotics/xacro-update
Updating xacro and favourites
2 parents 4a7aa99 + f68f9be commit 350c75b

File tree

14 files changed

+34
-91
lines changed

14 files changed

+34
-91
lines changed

src/lab_sim/description/picknik_ur.xacro

Lines changed: 7 additions & 46 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,9 @@
77
<material name="plastic">
88
<color rgba="0.1 0.1 0.1 1" />
99
</material>
10+
<material name="offwhite">
11+
<color rgba="0.01 0.01 0.01 1" />
12+
</material>
1013
<link name="world" />
1114
<joint name="tool_changer_joint" type="fixed">
1215
<!-- The parent link must be read from the robot model it is attached to. -->
@@ -1174,57 +1177,15 @@
11741177
<!-- Table -->
11751178
<link name="table">
11761179
<visual>
1177-
<origin rpy="0 0 0" xyz="0 0 0.025" />
1178-
<geometry>
1179-
<mesh
1180-
filename="package://picknik_accessories/descriptions/furniture/generic_table/wood_block.dae"
1181-
scale="0.125 0.125 0.00625"
1182-
/>
1183-
</geometry>
1184-
</visual>
1185-
<visual>
1186-
<origin rpy="0 0 0" xyz="0.4 0.4 -0.2" />
1187-
<geometry>
1188-
<box size="0.04 0.04 0.45" />
1189-
</geometry>
1190-
<material name="grey">
1191-
<color rgba="0.1 0.1 0.1 1.0" />
1192-
</material>
1193-
</visual>
1194-
<visual>
1195-
<origin rpy="0 0 0" xyz="0.4 -0.4 -0.2" />
1196-
<geometry>
1197-
<box size="0.04 0.04 0.45" />
1198-
</geometry>
1199-
<material name="grey">
1200-
<color rgba="0.1 0.1 0.1 1.0" />
1201-
</material>
1202-
</visual>
1203-
<visual>
1204-
<origin rpy="0 0 0" xyz="-0.4 -0.4 -0.2" />
1180+
<origin rpy="0 0 0" xyz="0 0 -0.45" />
12051181
<geometry>
1206-
<box size="0.04 0.04 0.45" />
1182+
<box size="3.5 1 0.9" />
12071183
</geometry>
1208-
<material name="grey">
1209-
<color rgba="0.1 0.1 0.1 1.0" />
1210-
</material>
1211-
</visual>
1212-
<visual>
1213-
<origin rpy="0 0 0" xyz="-0.4 0.4 -0.2" />
1214-
<geometry>
1215-
<box size="0.04 0.04 0.45" />
1216-
</geometry>
1217-
<material name="grey">
1218-
<color rgba="0.1 0.1 0.1 1.0" />
1219-
</material>
12201184
</visual>
12211185
<collision>
1222-
<origin rpy="0 0 0" xyz="0 0 0" />
1186+
<origin rpy="0 0 0" xyz="0 0 -0.45" />
12231187
<geometry>
1224-
<mesh
1225-
filename="package://picknik_accessories/descriptions/furniture/generic_table/wood_block.dae"
1226-
scale="0.125 0.125 0.00625"
1227-
/>
1188+
<box size="3.5 1 0.9" />
12281189
</geometry>
12291190
</collision>
12301191
</link>

src/lab_sim/objectives/apriltag_pick_object.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
<BehaviorTree
44
ID="Pick April Tag Labeled Object"
55
_description="Picks up an object that has an AprilTag marker."
6-
_favorite="false"
6+
_favorite="true"
77
>
88
<Control ID="Sequence" name="TopLevelSequence">
99
<SubTree ID="Look at table" _collapsed="true" />

src/lab_sim/objectives/constrained_pick_place.xml

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -51,8 +51,10 @@
5151
constraints="{constraints}"
5252
/>
5353
</Decorator>
54-
<!--Pick-->
55-
<SubTree ID="Close Gripper" />
54+
<!--We force success as the gripper closes, since we are commanding a position it will never reach (fingers fully closed)-->
55+
<Decorator ID="ForceSuccess">
56+
<SubTree ID="Close Gripper" />
57+
</Decorator>
5658
<!--Move to place (drop) location-->
5759
<Decorator ID="RetryUntilSuccessful" num_attempts="3">
5860
<SubTree
@@ -110,7 +112,9 @@
110112
waypoint_name="Place Cube"
111113
/>
112114
</Decorator>
113-
<SubTree ID="Close Gripper" />
115+
<Decorator ID="ForceSuccess">
116+
<SubTree ID="Close Gripper" />
117+
</Decorator>
114118
<Decorator ID="RetryUntilSuccessful" num_attempts="3">
115119
<SubTree
116120
ID="Move to Waypoint"

src/lab_sim/objectives/create_pose_vector.xml

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,6 @@
1-
<?xml version="1.0" encoding="utf-8" ?>
21
<root BTCPP_format="4" main_tree_to_execute="Create Pose Vector">
32
<!--//////////-->
4-
<BehaviorTree ID="Create Pose Vector">
3+
<BehaviorTree ID="Create Pose Vector" _favorite="false">
54
<Control ID="Sequence">
65
<Action
76
ID="CreateStampedPose"

src/lab_sim/objectives/load_and_execute_joint_trajectory.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717
/>
1818
<Action
1919
ID="LoadJointTrajectoryFromYaml"
20-
file_path="/home/michael/user_ws/src/lab_sim/objectives/joint_trajectory.yaml"
20+
file_path="joint_trajectory.yaml"
2121
/>
2222
<Action ID="ExecuteFollowJointTrajectory" />
2323
</Control>

src/lab_sim/objectives/look_at_table.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<root BTCPP_format="4" main_tree_to_execute="Look at table">
22
<!--//////////-->
3-
<BehaviorTree ID="Look at table" _description="" _favorite="false">
3+
<BehaviorTree ID="Look at table" _description="" _favorite="true">
44
<Control ID="Sequence" name="TopLevelSequence">
55
<SubTree
66
ID="Move to Waypoint"

src/lab_sim/objectives/move_with_velocity_and_force.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
<BehaviorTree
44
ID="Move until Force Contact"
55
_description="An example for how to use the VFC to move with a velocity / force reference until it collides"
6-
_favorite="false"
6+
_favorite="true"
77
>
88
<Control ID="Sequence" name="TopLevelSequence">
99
<SubTree

src/lab_sim/objectives/place_object.xml

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,11 @@
1-
<root BTCPP_format="4" main_tree_to_execute="Place object">
1+
<root BTCPP_format="4" main_tree_to_execute="Place Object">
22
<!--//////////-->
3-
<BehaviorTree ID="Place object" _description="" _favorite="false">
3+
<BehaviorTree
4+
ID="Place Object"
5+
_description=""
6+
_favorite="false"
7+
_subtreeOnly="false"
8+
>
49
<Control ID="Sequence" name="root">
510
<Control ID="Sequence">
611
<Action ID="SwitchUIPrimaryView" primary_view_name="Visualization" />

src/lab_sim/objectives/record_trajectory.xml

Lines changed: 0 additions & 29 deletions
This file was deleted.

src/lab_sim/objectives/register_cad_part.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<root BTCPP_format="4" main_tree_to_execute="Register CAD Part">
22
<!--//////////-->
3-
<BehaviorTree ID="Register CAD Part" _description="" _favorite="false">
3+
<BehaviorTree ID="Register CAD Part" _description="" _favorite="true">
44
<Control ID="Sequence" name="TopLevelSequence">
55
<Action ID="ClearSnapshot" />
66
<SubTree ID="Look at table" _collapsed="true" />

0 commit comments

Comments
 (0)