HEBI C++ Examples: Arm Node
The arm node can be used to provide high level commands to a HEBI robot arm.
https://github.com/HebiRobotics/hebi_cpp_api_ros_examples/tree/master/src/kits/arm
Installation / Build
To install all dependencies in a new catkin workspace, run the following steps (replace <ros-distro> with kinetic or melodic`):
sudo apt install ros-<ros-distro>-hebi-cpp-api mkdir -p ~/catkin_ws/src cd ~/catkin_ws/src git clone https://github.com/HebiRobotics/hebi_cpp_api_ros_examples.git hebi_cpp_api_examples cd .. catkin_make
Alternatively, if you wish to build using the source package of the C++ API (this will receive the latest changes before the apt installable debian package), run the following steps:
mkdir -p ~/catkin_ws/src cd ~/catkin_ws/src git clone https://github.com/HebiRobotics/hebi_cpp_api_ros.git hebi_cpp_api git clone https://github.com/HebiRobotics/hebi_cpp_api_ros_examples.git hebi_cpp_api_examples cd .. catkin_make
Parameters
The parameters define the modules on the network that the arm node will try to connect to, as well as how they are physically connected. The parameter files are in the config directory; several default ones are provided for standard HEBI kits.
Ensure the families and names parameters match the module family and names, ordered from proximal to distal, of your robot, and that these modules are visible on the network from your computer. Use HEBI Scope (downloadable from http://docs.hebi.us/downloads_changelogs.html#downloads) to discover and configure modules on your network.
You may also need to modify the parameters for the location of the gains file, HRDF file, and home position of the system.
Running
roslaunch hebi_cpp_api_examples arm_node.launch arm_type:=<arm_type>
Where arm_type is one of the HEBI Arm kit types with a matching parameter file in config/ (e.g., a-2085-04, a-2085-05, a-2085-06, etc).
Topics
TODO: graph
/offset_target (geometry_msgs::Point) Jog the end effector in the given cartesian direction relative to the base.
/cartesian_waypoints (hebi_cpp_api_examples::TargetWaypoint) Command the arm to move through a series of cartesian-space (relative to the base) waypoints
/joint_waypoints (trajectory_msgs::JointTrajectory) Command the arm to move through a series of joint-space waypoints
Note: for the JointTrajectory messages, you can ignore the header and the "names" fields, as well as the "efforts". You must fill in the "positions", "velocities", and "accelerations" vectors for each waypoint, along with the desired time_from_start for each waypoint (these must be monotonically increasing). For example, the following would be a valid motion for a 6-DoF arm:
rostopic pub /joint_waypoints trajectory_msgs/JointTrajectory "header: seq: 0 stamp: secs: 0 nsecs: 0 frame_id: '' joint_names: - '' points: - positions: [0.51, 2.09439, 2.09439, 0.01, 1.5707963, 0.01] velocities: [0, 0, 0, 0, 0, 0] accelerations: [0, 0, 0, 0, 0, 0] effort: [] time_from_start: {secs: 0, nsecs: 0} - positions: [0.01, 2.09439, 2.09439, 0.01, 1.5707963, 0.01] velocities: [0, 0, 0, 0, 0, 0] accelerations: [0, 0, 0, 0, 0, 0] effort: [] time_from_start: {secs: 5, nsecs: 0} - positions: [-0.51, 2.09439, 2.09439, 0.01, 1.5707963, 0.01] velocities: [0, 0, 0, 0, 0, 0] accelerations: [0, 0, 0, 0, 0, 0] effort: [] time_from_start: {secs: 10, nsecs: 0}" - positions: [-0.01, 2.09439, 2.09439, 0.01, 1.5707963, 0.01] velocities: [0, 0, 0, 0, 0, 0] accelerations: [0, 0, 0, 0, 0, 0] effort: [] time_from_start: {secs: 15, nsecs: 0}"
/compliant_mode (std_msgs::Bool) Toggle position control to allow the robot to be moved by hand.
/motion (action, hebi_cpp_api_examples::ArmMotion) Use a ROS action to move the robot to a given cartesian location of change LED colors.
* /joint_states (sensor_msgs::JointState) Provide joint angle, velocity, and effort feedback directly from the actuators in the arm.
Walkthrough Video
TODO