|
| 1 | +#!/usr/bin/env python |
| 2 | + |
| 3 | +"""Small example script to show that the joint position are not pushed ouside the joint |
| 4 | +limits when the `set_franka_model_configuration` service that was implemented in |
| 5 | +https://github.com/frankaemika/franka_ros/pull/226 is used. |
| 6 | +""" # noqa: E501 |
| 7 | + |
| 8 | +import numpy as np |
| 9 | +import rospy |
| 10 | +from franka_msgs.srv import SetJointConfiguration, SetJointConfigurationRequest |
| 11 | +from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint |
| 12 | + |
| 13 | +# Robot info. |
| 14 | +JOINT_NAMES = [ |
| 15 | + "panda_joint1", |
| 16 | + "panda_joint2", |
| 17 | + "panda_joint3", |
| 18 | + "panda_joint4", |
| 19 | + "panda_joint5", |
| 20 | + "panda_joint6", |
| 21 | + "panda_joint7", |
| 22 | + "panda_finger_joint1", |
| 23 | + "panda_finger_joint2", |
| 24 | +] |
| 25 | +JOINT_LIMITS = { |
| 26 | + "min": [-2.8973, -2.7628, -2.8973, -3.071, -2.8973, -0.0175, -2.8973, 0.0, 0.0], |
| 27 | + "max": [2.8973, 1.7628, 2.8973, -0.0698, 2.8973, 3.7525, 2.8973, 0.04, 0.04], |
| 28 | +} |
| 29 | +JOINT_INITIAL_POSITIONS = [0.0] * len(JOINT_NAMES) |
| 30 | + |
| 31 | + |
| 32 | +def set_random_joint_positions(joint_positions): |
| 33 | + """Set the joint positions of the robot using the Gazebo 'set_franka_model_configuration' |
| 34 | + service. |
| 35 | +
|
| 36 | + Args: |
| 37 | + joint_positions (list): A list of joint positions. |
| 38 | + """ |
| 39 | + try: |
| 40 | + set_model_configuration = rospy.ServiceProxy( |
| 41 | + "/set_franka_model_configuration", SetJointConfiguration |
| 42 | + ) |
| 43 | + request = SetJointConfigurationRequest() |
| 44 | + request.configuration.name = JOINT_NAMES |
| 45 | + request.configuration.position = joint_positions |
| 46 | + set_model_configuration(request) |
| 47 | + rospy.loginfo("Set joint positions to: %s", joint_positions) |
| 48 | + except rospy.ServiceException as e: |
| 49 | + rospy.logerr("Failed to call set_franka_model_configuration service: %s", e) |
| 50 | + |
| 51 | + |
| 52 | +if __name__ == "__main__": |
| 53 | + rospy.init_node("set_random_joint_positions") |
| 54 | + |
| 55 | + # x = True |
| 56 | + # while x: |
| 57 | + # pass |
| 58 | + |
| 59 | + # Set random joint positions within the joint limits. |
| 60 | + try: |
| 61 | + joint_positions = [ |
| 62 | + np.random.uniform(low, high) |
| 63 | + for low, high in zip(JOINT_LIMITS["min"], JOINT_LIMITS["max"]) |
| 64 | + ] |
| 65 | + set_random_joint_positions(joint_positions) |
| 66 | + except rospy.exceptions.ROSException as e: |
| 67 | + rospy.logerr("Failed to set random joint positions: %s", e) |
| 68 | + |
| 69 | + # Repeat the above every 5 seconds. |
| 70 | + rate = rospy.Rate(0.2) |
| 71 | + while not rospy.is_shutdown(): |
| 72 | + rate.sleep() |
| 73 | + try: |
| 74 | + joint_positions = [ |
| 75 | + np.random.uniform(low, high) |
| 76 | + for low, high in zip(JOINT_LIMITS["min"], JOINT_LIMITS["max"]) |
| 77 | + ] |
| 78 | + set_random_joint_positions(joint_positions) |
| 79 | + except rospy.exceptions.ROSException as e: |
| 80 | + rospy.logerr("Failed to set random joint positions: %s", e) |
| 81 | + |
| 82 | + # Reset the joint positions to their initial values when the node is shut down. |
| 83 | + joint_trajectory = JointTrajectory() |
| 84 | + joint_trajectory.joint_names = JOINT_NAMES |
| 85 | + joint_trajectory.points.append( |
| 86 | + JointTrajectoryPoint(positions=JOINT_INITIAL_POSITIONS) |
| 87 | + ) |
| 88 | + try: |
| 89 | + pub = rospy.Publisher( |
| 90 | + "/panda_arm_controller/command", JointTrajectory, queue_size=10 |
| 91 | + ) |
| 92 | + pub.publish(joint_trajectory) |
| 93 | + except rospy.exceptions.ROSException as e: |
| 94 | + rospy.logerr("Failed to reset joint positions: %s", e) |
0 commit comments