5 from moveit_commander
import MoveGroupCommander
7 if __name__ ==
'__main__':
10 rospy.init_node(
'message', anonymous=
True)
11 group = MoveGroupCommander(
"manipulator")
16 rospy.loginfo(
"joint1 start")
17 group.set_max_velocity_scaling_factor(exec_vel)
18 group.set_joint_value_target([0.1, 0.1, 0.1, 0.1, 0.1, 0.1])
20 rospy.loginfo(
"joint1 end")
22 rospy.loginfo(
"pose1 start")
23 group.set_max_velocity_scaling_factor(exec_vel)
24 group.set_pose_target([0.5,-0.2,0.2,0.0,1.0,0.0])
26 rospy.loginfo(
"pose1 end")
28 rospy.loginfo(
"pose2 start")
29 group.set_max_velocity_scaling_factor(exec_vel)
30 group.set_pose_target([0.5,-0.2,0.7,0.0,1.0,0.0])
32 rospy.loginfo(
"pose2 end")
34 rospy.loginfo(
"pose3 start")
35 group.set_max_velocity_scaling_factor(exec_vel)
36 group.set_pose_target([0.5,0.1,0.7,0.0,1.0,0.0])
38 rospy.loginfo(
"pose3 end")
40 rospy.loginfo(
"pose4 start")
41 group.set_max_velocity_scaling_factor(exec_vel)
42 group.set_pose_target([0.5,0.1,0.2,0.0,1.0,0.0])
44 rospy.loginfo(
"pose4 end")