hand_mapping = hand_parameters.mapping[hand_serial]

# Hand joints are detected
joints = hand_finder.get_hand_joints()[hand_mapping]

position_values = [0.35, 0.18, 0.38]

# Moving to a target determined by the values in position_values.
rospy.loginfo("Hand moving to script specified target")
position_1 = dict(zip(joints, position_values))
hand_commander.move_to_joint_value_target(position_1)

named_target_1 = "pack"
rospy.loginfo("Hand moving to named target: " + named_target_1)
hand_commander.move_to_named_target(named_target_1)

named_target_2 = "open"
rospy.loginfo("Hand moving to named target: " + named_target_2)
hand_commander.move_to_named_target(named_target_2)

# Hand joints state, velocity and effort are read and displayed to screen.
hand_joints_state = hand_commander.get_joints_position()
hand_joints_velocity = hand_commander.get_joints_velocity()
hand_joints_effort = hand_commander.get_joints_effort()

rospy.loginfo("Hand joints position \n " + str(hand_joints_state) + "\n")
rospy.loginfo("Hand joints velocity \n " + str(hand_joints_velocity) + "\n")
rospy.loginfo("Hand joints effort \n " + str(hand_joints_effort) + "\n")

# Tactile type and state are read and displayed to screen.
example_pose_1 = [0.6, 0.3, 1.5, -0.7, 0.04, -0.67]

example_pose_2 = [0.6, 0.3, 1.46, -0.7, 0.04, 0.69, 0.08]

example_pose_3 = [0.69, 0.64, 1.4, -0.71, 0.04, 0.69, 0.08]

# Start arm at home
rospy.loginfo("Moving arm to joint states\n" + str(arm_home_joints_goal) +
              "\n")
robot_commander.move_to_joint_value_target_unsafe(arm_home_joints_goal, 6.0,
                                                  True)

# Move hand to open
# Moving to a stored named target, stored targets can be viewed in MoveIt in the planning tab
rospy.loginfo("Moving hand to joint state: open")
hand_commander.move_to_named_target("open")
rospy.sleep(3.0)

# Move hand to pack
# Moving to a stored named target, stored targets can be viewed in MoveIt in the planning tab
rospy.loginfo("Moving hand to joint state: pack")
hand_commander.move_to_named_target("pack")

# The arm commander generates a plan to a new pose before the pose is executed.
input("Press Enter to continue...")
rospy.loginfo("Planning the move to the first pose:\n" + str(example_pose_1) +
              "\n")
arm_commander.plan_to_pose_target(example_pose_1)
rospy.loginfo("Finished planning, moving the arm now.")
# Can only execute if a plan has been generated.
arm_commander.execute()
Exemple #3
0
import rospy
from sr_robot_commander.sr_hand_commander import SrHandCommander
from sr_utilities.hand_finder import HandFinder
import geometry_msgs.msg
import copy

rospy.init_node("hand_example_following_finger_traj", anonymous=True)

hand_finder = HandFinder()
hand_parameters = hand_finder.get_hand_parameters()
prefix = hand_parameters.mapping.values()[0]
hand_serial = hand_parameters.mapping.keys()[0]

# Close all fingers except thumb
hand_commander = SrHandCommander()
hand_commander.move_to_named_target("fingers_pack_thumb_open")

# Change to first finger group
group_id = prefix + "_first_finger"
hand_commander = SrHandCommander(name=group_id)

# Open first finger
hand_commander.move_to_named_target("first_finger_open")

rospy.sleep(4)

rospy.loginfo("\nMoving Index finger following a set of waypoints")

waypoints = []

start_pose = hand_commander.get_current_pose(reference_frame=prefix + "_palm")
from sr_robot_commander.sr_arm_commander import SrArmCommander
from sr_robot_commander.sr_hand_commander import SrHandCommander

rospy.init_node("grab_bottle_example", anonymous=True)

hand_commander = SrHandCommander()
arm_commander = SrArmCommander()

print("Executing moves:")

# start a bit higher
# arm_commander.move_to_named_target("gamma", True)

# approach
print("Approach bottle")
hand_commander.move_to_named_target("open_bottle", False)
arm_commander.move_to_named_target("approach_bottle", True)

# grab
print("Hold bottle")
arm_commander.move_to_named_target("hold_bottle", True)
hand_commander.move_to_named_target("hold_bottle", True)

# pour
print("Pour")
arm_commander.move_to_named_target("pour_bottle", True)

# release
print("Release bottle")
arm_commander.move_to_named_target("hold_bottle", True)
hand_commander.move_to_named_target("open_bottle", True)
Exemple #5
0
#
# You should have received a copy of the GNU General Public License along
# with this program.  If not, see <http://www.gnu.org/licenses/>.
#

from sr_robot_commander.sr_hand_commander import SrHandCommander
import rospy
from burn_in_states import warehouse_states
from sr_robot_commander.sr_robot_state_exporter import SrRobotStateExporter

rospy.init_node("burn_in_test")

commander = SrHandCommander()
exporter = SrRobotStateExporter(warehouse_states)

commander.move_to_named_target(warehouse_states["burn_4_hand"])

test_trajectory = exporter.convert_trajectory([{
    'name': "burn_1_hand",
    "interpolate_time": 0.5,
    'pause_time': 1
}, {
    'name': "burn_2_hand",
    "interpolate_time": 0.5,
    'pause_time': 1
}, {
    'name': "burn_3_hand",
    "interpolate_time": 0.5,
    'pause_time': 0.5
}, {
    'name': "burn_4_hand",