#################################### ##THIS PAGE WAS ORIGINALLY CREATED BY: Hans Toquica #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0=[[dynamixel_controllers/Tutorials/ConnectingToDynamixelBus|Connecting to Dynamixel Bus]] ## descriptive title for the tutorial ## title = Controlling the PhantomX Pincher Robot Arm ## multi-line description to be displayed in search ## description = This tutorial shows how to control the PhantomX Pincher Robot Arm with ROS via FTDI. ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link= ## next.1.link= ## what level user is this tutorial for ## level= AdvancedCategory ## keywords = Pincher, PhantomX, Dynamixel Motor #################################### <> {{attachment:PhantomXPincher.jpg|PhantomX Pincher AX-12 Manipulator| width=50%, align="right"}} It has come the time to move a precious didactic robot, the PhantomX Pincher AX-12 Robot Arm. This manipulator has 4 degrees of freedom, and it can be controlled with [[ROS]] via a FTDI interface. (Image on the right taken from [[#PhantomXPincher|1]]). <> == Setting the Robot Up == Be aware the robot is well mounted in the base where you are going to use it. {{{#!wiki caution With certain speed the robot may fall down or damage parts close to it. }}} Connect the robot via FTDI following the next diagram: {{attachment:ConnectionDiagram.png|Connection Diagram| width=100%}} You should result with something like: {{attachment:ConnectedRobot.jpg|Connection Example| width=100%}} note that the [[http://www.trossenrobotics.com/6-port-ax-mx-power-hub|Power Hub]] is being used here. Also note the computer being used here is a Raspberry Pi 3 Model B, however any computer with [[ROS]] in it should do the work. == Specifying the Controller Parameters == It is time to specify the parameters that will receive the dynamixel-controllers package in order to connect to the motors. It is assumed that you already know the motor ids, obtained in the tutorial [[dynamixel_controllers/Tutorials/ConnectingToDynamixelBus|Connecting to Dynamixel Bus]]. === The Parameters === Create a YAML file named tilt.yaml and paste the following in it. {{{ #!block=parameters waist_controller: controller: package: dynamixel_controllers module: joint_position_controller type: JointPositionController joint_name: waist_joint joint_speed: 0.17 motor: id: 1 init: 0 min: 0 max: 1023 shoulder_controller: controller: package: dynamixel_controllers module: joint_position_controller type: JointPositionController joint_name: shoulder_joint joint_speed: 0.17 motor: id: 2 init: 0 min: 0 max: 1023 elbow_controller: controller: package: dynamixel_controllers module: joint_position_controller type: JointPositionController joint_name: elbow_joint joint_speed: 0.17 motor: id: 3 init: 0 min: 0 max: 1023 wrist_controller: controller: package: dynamixel_controllers module: joint_position_controller type: JointPositionController joint_name: wrist_joint joint_speed: 0.17 motor: id: 4 init: 0 min: 0 max: 1023 hand_controller: controller: package: dynamixel_controllers module: joint_position_controller type: JointPositionController joint_name: hand_joint joint_speed: 0.17 motor: id: 5 init: 0 min: 0 max: 1023 }}} === The YAML file explained === A quick look at the objects created before let us know the parameters that are being sent to the dynamixel_controllers package <> sets an object called {{{waist_controller}}} (this can be changed at your will, it will also change the topic name for the commands you send to it), with 4 attributes: controller, joint_name, joint_speed and motor. From these for parameters, the only arbitrary is the joint_name. <> Makes the controller package to be dynamixel_controllers and lets it know the motor is being set will be working in joint mode (not wheel mode). <> Sets the motor speed to 0.17 radians per second, this is very important for the set up because when running the controller it will go to the initial position, if the speed is too high damage can be made to the robot. This can be changed in your node after you set things up ;). <> The motor attribute also has sub-attributes, between them, the motor {{{id}}}, it is important that you remember which motor you are setting with each object you are creating here and that you can recall the name of the object for each motor. {{{init}}} sets the initial position for the motor, you may refer to [[dynamixel_controllers/Tutorials/CreatingJointPositionController#ControllerParameters|Creating a Joint Controller]] for more information about the motor's actual angle limits. {{{#!wiki caution You don't want to exceed the 1023 value in either of the joints if you don't want to hurt your robot. }}} {{{min}}} and {{{max}}} are the minimum and maximum angle values, respectively, and the previous note also applies for these values. The rest of the file represents the objects created for the other motors. == Linking the Controller == The controller manager created in [[dynamixel_controllers/Tutorials/ConnectingToDynamixelBus|Connecting to Dynamixel Bus]] shall be linked to by means of using another launch file. {{{ }}} == Starting it up == In order to use the controller run {{{ roslaunch my_dynamixel_tutorial controller_manager.launch }}} To make the controller manager available and to prove accessibility to the robot motors, then run {{{ roslaunch my_dynamixel_tutorial start_tilt_controller.launch }}} == Move your Robot == A quick look at {{{rostopic list}}} let us see the topics available, among which we will find {{{waist_controller/command}}}, {{{shoulder_controller/command}}}, {{{elbow_controller/command}}}, {{{wrist_controller/command}}} and {{{hand_controller/command}}}, there are the topics you have to publish to in order to move the robot. You may want to try the following in a terminal. {{{ rostopic pub -1 /waist_controller/command std_msgs/Float64 -- 2.61 rostopic pub -1 /shoulder_controller/command std_msgs/Float64 -- 2.61 rostopic pub -1 /elbow_controller/command std_msgs/Float64 -- 2.61 rostopic pub -1 /wrist_controller/command std_msgs/Float64 -- 2.61 rostopic pub -1 /hand_controller/command std_msgs/Float64 -- 2.61 }}} == Acknowledgment Notice == This tutorial was created by [[HansToquica|Hans Toquica]], feel free to contact me at [[mailto:toquica@engineer.com?subject=About PhantomX Pincher Manipulator|toquica@engineer.com]] in case you have any questions in regards of this way of connecting to the robot. == References == 1. <> PhantomX Pincher Robot Arm Kit Mark II - Turtlebot Arm. N.a. Trossen Robotics. http://www.trossenrobotics.com/p/PhantomX-Pincher-Robot-Arm.aspx (Retrieved Nov-7-2017). ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE