Note: This tutorial assumes that you have completed the previous tutorials: connecting to Dynamixel bus.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Creating a dynamixel action client controller

Description: This tutorial describes how to create a joint controller with one or more Robotis Dynamixel motors.

Tutorial Level:

All files that are created in this tutorial should be saved into my_dynamixel_tutorial package which we have created in previous tutorial.

roscd my_dynamixel_tutorial

Step1: Create a client

   1 #!/usr/bin/env python
   2 import roslib
   3 roslib.load_manifest('my_dynamixel_tutorial')
   4 
   5 import rospy
   6 import actionlib
   7 from std_msgs.msg import Float64
   8 import trajectory_msgs.msg
   9 import control_msgs.msg
  10 from trajectory_msgs.msg import JointTrajectoryPoint
  11 from control_msgs.msg import JointTrajectoryAction, JointTrajectoryGoal, FollowJointTrajectoryAction, FollowJointTrajectoryGoal
  12 
  13 
  14 
  15 class Joint:
  16         def __init__(self, motor_name):
  17             #arm_name should be b_arm or f_arm
  18             self.name = motor_name
  19             self.jta = actionlib.SimpleActionClient('/'+self.name+'_controller/follow_joint_trajectory', FollowJointTrajectoryAction)
  20             rospy.loginfo('Waiting for joint trajectory action')
  21             self.jta.wait_for_server()
  22             rospy.loginfo('Found joint trajectory action!')
  23 
  24 
  25         def move_joint(self, angles):
  26             goal = FollowJointTrajectoryGoal()
  27             char = self.name[0] #either 'f' or 'b'
  28             goal.trajectory.joint_names = ['joint_1'+char, 'joint_2'+char,'joint_3'+char]
  29             point = JointTrajectoryPoint()
  30             point.positions = angles
  31             point.time_from_start = rospy.Duration(3)
  32             goal.trajectory.points.append(point)
  33             self.jta.send_goal_and_wait(goal)
  34 
  35 
  36 def main():
  37             arm = Joint('f_arm')
  38             arm.move_joint([0.5,1.5,1.0])
  39             arm.move_joint([6.28,3.14,6.28])
  40 
  41 
  42 if __name__ == '__main__':
  43       rospy.init_node('joint_position_tester')
  44       main()

The Code Explained

Now, let's break down the code piece by piece.

Error: No code_block found Library used for send a trajectory point

Error: No code_block found Remember to add the dependecies to your manifest

Error: No code_block found Library with action messages

Error: No code_block found Create a client through the topic namespace/name_of_server.In this case the namespace is self.name wich would be b_arm f_arm depends on witch arm do you wanna move, so remember to create a meta controller for b_arms and for f_arms, you can check this at previous tutorial.

Error: No code_block found Get the namespace first character that should be b or f and then add this to the trajectory joint names, that should match with joint names in your configuration file (config.yaml), you can review at previous tutorial.

Error: No code_block found send 0.5,1.5,1.0 positions for respectives joints joint_1x, joint_2x, joint_3x

Step2: Executing a client

After you create the client you should launch the controllers and spawners created in previous tutorial.

roslaunch my_dynamixel_tutorial start_meta_controller.launch

and then execute the client

roscd my_dynamixel_tutorial
python trajectory_client.py

now see motors move in a trajectory!!

Wiki: dynamixel_controllers/Tutorials/Creatingdynamixelactionclient (last edited 2018-04-17 18:51:54 by Everton.Cerqueira)