Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions src/moveit_pro_ur_configs/bring_it_sim/description/bar.xml
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@
friction="0.8 0.2"
/>
</body>
<body name="beer_bottle_3" pos="0 2 0.9">
<body name="beer_bottle_3" pos="0 1.5 0.9">
<freejoint />
<site name="beer_bottle_3" />
<geom
Expand All @@ -77,7 +77,7 @@
friction="0.8 0.2"
/>
</body>
<body name="beer_bottle_4" pos="0.5 2 0.9">
<body name="beer_bottle_4" pos="0.5 1.5 0.9">
<freejoint />
<site name="beer_bottle_4" />
<geom
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@
<param name="render_publish_rate">60</param>
<param name="tf_publish_rate">60</param>
<param name="lidar_publish_rate">10</param>
<param name="ignore_joint_validation">linear_x_joint linear_y_joint rotational_yaw_joint world_bar world_beer_bottle_1 world_beer_bottle_2 world_beer_bottle_3 world_beer_bottle_4 world_beer_bottle_5 world_table_1 world_table_2 world_table_3 world_table_4</param>
<param name="ignore_joint_validation">linear_x_joint linear_y_joint rotational_yaw_joint</param>
<param name="publish_odom">true</param>
<param name="odom_child_frame">ridgeback_base_link</param>
<param name="odom_zero_z">true</param>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
<xacro:include filename="$(find bring_it_sim)/description/picknik_ur_attachments_macro.xacro"/>
<xacro:include filename="$(find bring_it_sim)/description/picknik_ur_mujoco_ros2_control.xacro"/>
<xacro:include filename="$(find ridgeback_description)/urdf/ridgeback.urdf.xacro"/>
<xacro:include filename="$(find bring_it_sim)/description/bar.xacro"/>

<link name="world"/>

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
<?xml version="1.0" encoding="UTF-8" ?>
<root BTCPP_format="4" main_tree_to_execute="Move close to bar">
<!--//////////-->
<BehaviorTree
ID="Move close to bar"
_description="Move close enough to the bar to pick up a beer"
_favorite="true"
>
<Control ID="Sequence">
<Action
ID="CreateStampedPose"
orientation_xyzw="0;0;0;1"
position_xyz="0;1;0"
stamped_pose="{home_location}"
reference_frame="world"
/>
<Action
ID="VisualizeMesh"
mesh_path="package://bring_it_sim/description/assets/locationmarker.dae"
mesh_pose="{home_location}"
/>
<Action
ID="NavigateToPoseAction"
pose_stamped="{home_location}"
behavior_tree_path="/opt/ros/humble/share/nav2_bt_navigator/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml"
action_name="/navigate_to_pose"
/>
</Control>
</BehaviorTree>
<TreeNodesModel>
<SubTree ID="Move close to bar" />
</TreeNodesModel>
</root>
39 changes: 39 additions & 0 deletions src/moveit_pro_ur_configs/bring_it_sim/objectives/pick_beer.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
<?xml version="1.0" encoding="UTF-8" ?>
<root BTCPP_format="4" main_tree_to_execute="Pick beer">
<!--//////////-->
<BehaviorTree
ID="Pick beer"
_description=""
_favorite="false"
_subtreeOnly="true"
name=""
>
<Control ID="Sequence" name="root">
<SubTree ID="Open Gripper" />
<Control ID="Sequence">
<Action
ID="CreateStampedPose"
orientation_xyzw="1;0;0;0"
position_xyz="0;0;0.22"
reference_frame="{beer_frame}"
/>
<Action ID="VisualizePose" />
<Action
ID="AddPoseStampedToVector"
input="{stamped_pose}"
vector="{pose_vector}"
/>
</Control>
<SubTree
ID="Pick first object in vector"
pose_vector="{pose_vector}"
_collapsed="false"
/>
</Control>
</BehaviorTree>
<TreeNodesModel>
<SubTree ID="Pick beer">
<input_port name="beer_frame" default="{frame_id}" />
</SubTree>
</TreeNodesModel>
</root>
16 changes: 16 additions & 0 deletions src/moveit_pro_ur_configs/bring_it_sim/objectives/pick_up_beer.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0" encoding="UTF-8" ?>
<root BTCPP_format="4" main_tree_to_execute="Pick up Beer">
<!--//////////-->
<BehaviorTree ID="Pick up Beer" _description="" _favorite="true">
<Control ID="Sequence" name="TopLevelSequence">
<SubTree ID="Clear Snapshot" _collapsed="true" />
<SubTree ID="Look at table" _collapsed="true" />
<!--Take a snapshot so we have a visualization of the cubes to use in grasp pose correction-->
<SubTree ID="Take scene camera snapshot" _collapsed="true" />
<SubTree ID="Pick beer" _collapsed="true" beer_frame="{frame_id}" />
</Control>
</BehaviorTree>
<TreeNodesModel>
<SubTree ID="Pick up Beer" />
</TreeNodesModel>
</root>
Original file line number Diff line number Diff line change
Expand Up @@ -199,7 +199,7 @@ local_costmap:
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.55
inflation_radius: 0.20
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
Expand Down Expand Up @@ -264,7 +264,7 @@ global_costmap:
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.55
inflation_radius: 0.20
always_send_full_costmap: True

map_server:
Expand Down
98 changes: 83 additions & 15 deletions src/moveit_pro_ur_configs/bring_it_sim/waypoints/ur_waypoints.yaml
Original file line number Diff line number Diff line change
@@ -1,48 +1,69 @@
- description: ''
- description: ""
favorite: true
joint_group_names:
- gripper
- linear_actuator
- manipulator
- wheel_actuator
joint_state:
effort: []
header:
frame_id: ''
frame_id: ""
stamp:
nanosec: 0
sec: 0
name:
- robotiq_85_left_knuckle_joint
- linear_x_joint
- linear_y_joint
- rotational_yaw_joint
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
- wrist_1_joint
- shoulder_lift_joint
- front_rocker
- front_left_wheel
- front_right_wheel
- rear_left_wheel
- rear_right_wheel
position:
- -8.704708810562631e-06
- 1.4068654234675446
- 1.56799762591031
- 8.888612690481538e-10
- 0.782482319413393
- -1.2156111214535257
- 0.1025781249307494
- 0
- 0
- 0
- 0.8371631576820436
- -0.3352390746492166
- 0.19765088507041076
- -2.3182411494283217
- -1.4856134479671956
- -0.059141607883296456
- 6.680871677833013e-05
- -5.2400322737957
- 5.2356089836249575
- -5.238369713479739
- 5.233722234090497
velocity: []
multi_dof_joint_state:
header:
frame_id: ''
frame_id: ""
stamp:
nanosec: 0
sec: 0
joint_names: []
transforms: []
twist: []
wrench: []
name: Look at Table
- description: ''
name: Near bottle 3
- description: ""
favorite: true
joint_group_names:
- manipulator
joint_state:
effort: []
header:
frame_id: ''
frame_id: ""
stamp:
nanosec: 0
sec: 0
Expand All @@ -63,7 +84,7 @@
velocity: []
multi_dof_joint_state:
header:
frame_id: ''
frame_id: ""
stamp:
nanosec: 0
sec: 0
Expand All @@ -72,3 +93,50 @@
twist: []
wrench: []
name: Stowed
- description: ""
favorite: true
joint_group_names:
- gripper
- linear_actuator
- manipulator
joint_state:
effort: []
header:
frame_id: ""
stamp:
nanosec: 0
sec: 0
name:
- robotiq_85_left_knuckle_joint
- linear_x_joint
- linear_y_joint
- rotational_yaw_joint
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
position:
- 0
- 0.4
- 0.4
- 1
- 0
- -1.5708
- 0.785398
- -1.2948195437205516
- -1.5708
- 0
velocity: []
multi_dof_joint_state:
header:
frame_id: ""
stamp:
nanosec: 0
sec: 0
joint_names: []
transforms: []
twist: []
wrench: []
name: Look at Table
Loading