Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add pick demo with hey5. Work in progress #21

Open
wants to merge 2 commits into
base: kinetic-devel
Choose a base branch
from
Open
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
63 changes: 63 additions & 0 deletions tiago_pick_demo/config/pick_and_place_params_titanium.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
# Desired distance from grasp_postures_frame_id to put the object
# So, the grasping point
grasp_desired_distance: 0.10
grasp_min_distance: 0.0
# Times for the grasp, they are sumed step after step
time_pre_grasp_posture: 2.0
time_grasp_posture: 1.0
time_grasp_posture_final: 3.0
# Base frame of MoveIt for your robot
grasp_pose_frame_id: base_footprint
# Frame where the direction of the poses will be computed
grasp_postures_frame_id: arm_tool_link
# Currently unused grasp quality to put in the message
grasp_quality: 0.1
# Gripper joint poses
gripper_joint_names: "hand_thumb_joint hand_index_joint hand_mrl_joint"
# Closed position
gripper_grasp_positions: "6.2 6.8 9.2"
# Open position
gripper_pre_grasp_positions: "0.0 0.0 .0"

# Direction in reference of the grasp_postures_frame_id
pre_grasp_direction_x: 1.0
pre_grasp_direction_y: 0.0
pre_grasp_direction_z: 0.0

# Direction in reference of the grasp_postures_frame_id
post_grasp_direction_x: -1.0
post_grasp_direction_y: 0.0
post_grasp_direction_z: 0.0

max_contact_force: 0.0
allowed_touch_objects: ''

# Rotation to apply if you have unaligned
# tool link to grasping frame
fix_tool_frame_to_grasping_frame_roll: 0.0
fix_tool_frame_to_grasping_frame_pitch: 0.0
fix_tool_frame_to_grasping_frame_yaw: 90.0

# Generation of grasps configuration
# in order to generate more or less poses these
# parameters can be tuned
min_degrees_yaw: 0
max_degrees_yaw: 360
min_degrees_pitch: 0
max_degrees_pitch: 360

# The steps are the main thing to tune
step_degrees_pitch: 15
step_degrees_yaw: 15

#links_to_allow_contact: ["gripper_left_finger_link", "gripper_right_finger_link", "gripper_link"]
links_to_allow_contact: [hand_safety_box, hand_palm_link, hand_index_abd_link, hand_index_flex_1_link, hand_index_flex_2_link, hand_index_flex_3_link,
hand_index_link, hand_index_virtual_1_link, hand_index_virtual_2_link, hand_index_virtual_3_link,
hand_little_abd_link, hand_little_flex_1_link, hand_little_flex_2_link, hand_little_flex_3_link,
hand_little_virtual_1_link, hand_little_virtual_2_link, hand_little_virtual_3_link,
hand_middle_abd_link, hand_middle_flex_1_link, hand_middle_flex_2_link, hand_middle_flex_3_link,
hand_middle_virtual_1_link, hand_middle_virtual_2_link, hand_middle_virtual_3_link,
hand_mrl_link, hand_ring_abd_link, hand_ring_flex_1_link, hand_ring_flex_2_link,
hand_ring_flex_3_link, hand_ring_virtual_1_link, hand_ring_virtual_2_link, hand_ring_virtual_3_link,
hand_thumb_abd_link, hand_thumb_flex_1_link, hand_thumb_flex_2_link, hand_thumb_link,
hand_thumb_virtual_1_link, hand_thumb_virtual_2_link]
8 changes: 5 additions & 3 deletions tiago_pick_demo/launch/pick_demo.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
<launch>

<arg name="rviz" default="true"/>
<arg name="robot" default="steel"/>
<!-- marker detector -->
<node pkg="aruco_ros" type="single" name="aruco_single">
<remap from="/camera_info" to="/xtion/rgb/camera_info" />
Expand All @@ -16,18 +17,19 @@
</node>

<!-- Load definition of pregrasp motion into play_motion namespace -->
<rosparam command="load" file="$(find tiago_pick_demo)/config/pick_motions.yaml" />
<rosparam command="load" file="$(find tiago_pick_demo)/config/pick_motions.yaml" />

<!-- Pick & place server -->
<node name="pick_and_place_server" pkg="tiago_pick_demo" type="pick_and_place_server.py" output="screen">
<rosparam command="load" file="$(find tiago_pick_demo)/config/pick_and_place_params.yaml" />
<rosparam command="load" file="$(find tiago_pick_demo)/config/pick_and_place_params_steel.yaml" if="$(eval arg('robot') == 'steel')"/>
<rosparam command="load" file="$(find tiago_pick_demo)/config/pick_and_place_params_titanium.yaml" if="$(eval arg('robot') == 'titanium')"/>
<param name="object_width" value="0.05" />
<param name="object_height" value="0.1" />
<param name="object_depth" value="0.05" />
</node>

<!-- Node exposing service to start looking for the object and trigger the picking -->
<node name="pick_client" pkg="tiago_pick_demo" type="pick_client.py" output="screen"/>
<node name="pick_client" pkg="tiago_pick_demo" type="pick_client.py" output="screen"/>

<group if="$(arg rviz)">
<node name="pick_demo_rviz" pkg="rviz" type="rviz" args="-d $(find tiago_pick_demo)/config/rviz/tiago_pick_demo.rviz" />
Expand Down