hebi_arm_tutorial
Differences
This shows you the differences between two versions of the page.
Both sides previous revisionPrevious revisionNext revision | Previous revision | ||
hebi_arm_tutorial [2020/10/15 15:56] – leogeorgescu | hebi_arm_tutorial [2020/11/20 05:16] (current) – jkreitz | ||
---|---|---|---|
Line 2: | Line 2: | ||
\\ | \\ | ||
**Author:** Leonardo Georgescu and Jason Kreitz\\ | **Author:** Leonardo Georgescu and Jason Kreitz\\ | ||
- | **Email:** [email protected]\\ | + | **Email:** georgl3@unlv.nevada.edu and kreitzj@unlv.nevada.edu\\ |
- | **Date:** Last Edited | + | **Date:** Last Edited |
- | **Keywords: | + | **Keywords: |
+ | \\ | ||
\\ | \\ | ||
Hebi arm is a 6 DoF arm that has a gripper and is able to pick and place objects. The benefit of the arm is that it has series elastic actuators. It also has force-torque sensors which I will be discussing how they work later. \\ | Hebi arm is a 6 DoF arm that has a gripper and is able to pick and place objects. The benefit of the arm is that it has series elastic actuators. It also has force-torque sensors which I will be discussing how they work later. \\ | ||
Line 64: | Line 65: | ||
For the full Gazebo simulator please see this github repository: https:// | For the full Gazebo simulator please see this github repository: https:// | ||
+ | \\ | ||
+ | \\ | ||
+ | <fs x-large> | ||
+ | \\ | ||
+ | Arm Model:= A-2085-06\\ | ||
+ | Home position: | ||
+ | \\ | ||
+ | |||
+ | Use the below bash script to install the ROS packages. | ||
+ | |||
+ | |||
+ | <code php> | ||
+ | sudo apt-get install ros-< | ||
+ | |||
+ | mkdir -p ~/ | ||
+ | cd ~/ | ||
+ | git clone https:// | ||
+ | git clone https:// | ||
+ | git clone https:// | ||
+ | cd .. | ||
+ | catkin_make | ||
+ | |||
+ | </ | ||
+ | |||
+ | **__Warning: | ||
+ | \\ | ||
+ | \\ | ||
+ | |||
+ | <fs large> | ||
+ | \\ | ||
+ | Open the file catkin_ws/ | ||
+ | \\ | ||
+ | |||
+ | Then, run the below script in order to start the Hebi Arm. | ||
+ | <code php> | ||
+ | roslaunch hebi_cpp_api_examples arm_teach_repeat_6_dof.launch | ||
+ | </ | ||
+ | |||
+ | In order to make the arm move, run the below script in a terminal. Make sure that index and mode are on new lines. | ||
+ | <code php> | ||
+ | rostopic pub /playback hebi_cpp_api_examples/ | ||
+ | index: 0 | ||
+ | mode: 2" | ||
+ | </ | ||
+ | |||
+ | Basically, the roslaunch will include the list of paths and waypoints from the txt files, and the arm_teach_repeat node will then load those paths and waypoints into named vectors. Those vectors can then be ran when you publish a “Playback” message (from hebi_cpp_api_examples/ | ||
+ | \\ | ||
+ | |||
+ | <fs large> | ||
+ | Run the following two scripts in separate terminals: | ||
+ | <code php> | ||
+ | rosrun hebi_cpp_api_examples arm_node | ||
+ | rosservice call -- / | ||
+ | </ | ||
+ | |||
+ | __**Topics that the arm listens to after running the above rosrun:**__ \\ | ||
+ | \\ | ||
+ | **1. / | ||
+ | This topic will jog the end effector in the given cartesian direction relative to the base. \\ | ||
+ | It requires a geometry_msgs:: | ||
+ | The below three lines is one example terminal command (make sure that y and z are on separate newlines): | ||
+ | | ||
+ | <code php> | ||
+ | rostopic pub / | ||
+ | y: 0.1 | ||
+ | z: 0.1" | ||
+ | </ | ||
+ | |||
+ | (I would recommend not moving more than 0.1 in any direction. The arm moves very fast, and moving it more than 0.1 in any direction will make it jump unsafely)\\ | ||
+ | If you want to use the offset in an actual client node, just create a publisher to publish a Point message to this topic.\\ | ||
+ | This mode would be useful for implementing the use of a game controller...\\ | ||
+ | \\ | ||
+ | | ||
+ | **2. / | ||
+ | Command the arm to move through a series of cartesian-space (relative to the base) waypoints \\ | ||
+ | Allows us to specify an array/queue of geometry_msgs/ | ||
+ | You can publish an array of Point messages on the topic as the waypoints_vector.\\ | ||
+ | The below lines are examples of terminal commands that we can use to publish on the topics. | ||
+ | |||
+ | <code php> | ||
+ | rostopic pub / | ||
+ | - x: 0.2 | ||
+ | y: 0.3 | ||
+ | z: 0.0" | ||
+ | | ||
+ | rostopic pub / | ||
+ | - x: 0.2 | ||
+ | y: 0.3 | ||
+ | z: 0.2" | ||
+ | | ||
+ | rostopic pub / | ||
+ | - x: 0.2 | ||
+ | y: 0.3 | ||
+ | z: 0.4" | ||
+ | </ | ||
+ | |||
+ | I'm personally not a big fan of this one. It doesn’t give the user control over the timing of queue execution. In addition, Point messages only allow for X, Y, Z movement – no end effector rotation. \\ | ||
+ | In reality, the end effector just moves around without any user control, and there’s nothing that the user can really do about it…\\ | ||
+ | \\ | ||
+ | |||
+ | **3. / | ||
+ | Command the arm to move through a series of joint-space waypoints \\ | ||
+ | Same as the above, except with trajectory messages in joint space (joint thetas, instead of cartesian coordinates of the end effector).\\ | ||
+ | This most likely will allow us to control the entire robot, including the end effector rotation (unlike the above), but it requires us to use our own IK solver if we want to use IK. I haven’t yet tested this one.\\ | ||
+ | \\ | ||
+ | \\ | ||
+ | **4. /motion (action, hebi_cpp_api_examples:: | ||
+ | Use a ROS action to move the robot to a given Cartesian location.\\ | ||
+ | Uses the ROS ActionLib API to give control over the robot queuing system. For more information on using the ROS ActionLib API, take a look at my RB5 ROS Wrapper at https:// | ||
+ | \\ | ||
+ | For some reason, their implementation is giving me errors. I have a simple test client that is passing the same parameters as cartesian_waypoints, | ||
+ | \\ | ||
+ | |||
+ | **In addition to the above, the current robot orientation information can be found by running the following in a terminal:** | ||
+ | <code php> | ||
+ | rostopic echo / | ||
+ | </ | ||
+ | |||
+ | Comments: I’m not too sure what set_ik_seed actually does, but I think (after reading – I could definitely use some clarification onto how the IK solver works) that the IK solver uses some sort of gradient descent for local minimum, and the ik_seed is required in order to set the initial test value. I used the home position as seed, and it works very well – even though it’s joint positions and not Cartesian. | ||
+ | |||
+ | Note/ | ||
+ | I got this value from the following link: https:// | ||
+ | \\ | ||
+ | |||
+ | <fs large> | ||
+ | |||
+ | Replace the following line in the file gripper_node.cpp in the src/ | ||
+ | <code php> | ||
+ | [Line 80] if (!gains_cmd.readGains(ros:: | ||
+ | </ | ||
+ | |||
+ | With the following lines of code: | ||
+ | <code php> | ||
+ | std::string myTest = ros:: | ||
+ | std:: | ||
+ | chars.push_back(' | ||
+ | char *c = & | ||
+ | if (!c) | ||
+ | </ | ||
+ | |||
+ | Then run the following line in one terminal to activate the gripper' | ||
+ | <code php> | ||
+ | rosrun hebi_cpp_api_examples gripper_node | ||
+ | </ | ||
+ | |||
+ | Afterwards, run the following line to close the gripper: | ||
+ | <code php> | ||
+ | rostopic pub / | ||
+ | </ | ||
+ | Note: You should be able to use any float between 0 and 1 for the above. Even if the gripper is closed, by turning up the effort value, you should be able to grip stronger... \\ | ||
+ | \\ | ||
+ | Or run the following line to open the gripper: | ||
+ | <code php> | ||
+ | rostopic pub / | ||
+ | </ | ||
+ | Again, we can write a node that publishes to these topics so that we can control the robot in our own client. |
hebi_arm_tutorial.1602802590.txt.gz · Last modified: 2020/10/15 15:56 by leogeorgescu