Note: This tutorial assumes that you have completed the previous tutorials: Control Modes, GUI Control. |
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. |
Waypoint Control
Description: Control the qb SoftHand Research and the qb SoftHand2 Research motion through an automatic waypoint trajectory loopKeywords: qbrobotics SoftHand control
Tutorial Level: INTERMEDIATE
Next Tutorial: API Control
This control mode is a bit more structured and useful than the previous: it allows to set a fixed trajectory of any number of position waypoints (with timing constraints) and set the robot to cycle infinitely on it (because of the loop it is recommended to set the first and last waypoint in a similar configuration to avoid unwanted sudden changes).
To start this mode just add use_waypoints:=true to the general roslaunch command (be sure that the opposite use_controller_gui is not used). You won't see any control interface in this case but the qb SoftHand should start moving according to the given trajectory, parsed from a yaml file located at ` <robot_package>_control/config/<robot_name>_waypoints.yaml ` where robot_name and robot_package are two additional launch file arguments.
Customization
You can modify the waypoint trajectory to replicate the behavior you want: either change the <robot_package>_control/config/<robot_name>_waypoints.yaml or add another custom application-specific file in the config directory. In the second case you need to set the argument robot_name properly when launching the command from the terminal.
The waypoint configuration depends on the device and is as follows for qb SoftHand Research:
# Waypoints describe the desired motion trajectory: # - time [s]: can be either a single value or an interval for which joint_positions hold # - joint_positions: # - hand closure [0,1]; # - joint_velocities: optional, use it only if you want a nonzero value # - hand closure [0,1]/s; # - joint_accelerations: optional, use it only if you want a nonzero value # - hand closure [0,1]/s^2; # # It is worth noting that, if specified, joint_positions, joint_velocities and joint_accelerations must be of size one. waypoints: - time: [1.0] joint_positions: <device_name>: [0.0] - time: [2.25, 2.75] joint_positions: <device_name>: [0.8] - time: [4.0] joint_positions: <device_name>: [0.5] - ...
For qb SoftHand2 Research instead it is necessary to send two commands:
# Waypoints describe the desired motion trajectory: # - time [s]: can be either a single value or an interval for which joint_positions hold # - joint_positions: # - hand closure [0,1]; # - joint_velocities: optional, use it only if you want a nonzero value # - hand closure [0,1]/s; # - joint_accelerations: optional, use it only if you want a nonzero value # - hand closure [0,1]/s^2; # # It is worth noting that, if specified, joint_positions, joint_velocities and joint_accelerations must be of size two. waypoints: - time: [1.0] joint_positions: <device_name>: [0.0, 1.0] - time: [2.25, 2.75] joint_positions: <device_name>: [1.0, 0.8] - time: [4.0] joint_positions: <device_name>: [-1.0, 0.5] ...