-
Notifications
You must be signed in to change notification settings - Fork 11
[B] Usage: Manipulator
This tutorial will show you the basics of controlling the youbot manipulator.
To use the API you can include the controller_api header (which also contains the base and gripper API) or only the youbot_arm header.
#include <luh_youbot_controller_api/controller_api.h>
// or
#include <luh_youbot_controller_api/youbot_arm.h>
###Initialisation
The first step is to initialise the ROS Node and to create a node handle.
//initialise ROS
ros::init(argc, argv, "my_youbot_node");
ros::NodeHandle node_handle;
Using the node handle the arm can be initialised.
youbot_api::YoubotArm arm;
arm.init(node_handle);
###Basic Position Commands
Position commands for the arm can be set using the moveToPose() method which has four overloads:
// for jointspace coordinates
void moveToPose(luh_youbot_kinematics::JointPosition pose,
int mode=MotionMode::PLAN,
bool pose_is_relative=false);
// for cylindrical coordinates
void moveToPose(luh_youbot_kinematics::CylindricPosition pose,
int mode=MotionMode::PLAN,
bool pose_is_relative=false);
// for cartesian coordinates
void moveToPose(luh_youbot_kinematics::CartesianPosition pose,
int mode=MotionMode::PLAN,
std::string frame_id="arm_link_0",
bool pose_is_relative=false);
// for predefined poses
void moveToPose(std::string pose_name,
int movement_mode=MotionMode::PLAN,
int interpolation_mode=InterpolationMode::JOINTSPACE);
The arguments are:
- pose: A pose defined in jointspace, cartesian or cylindrical coordinates using the luh_youbot_kinematics library.
- mode: The motion mode can be
- MotionMode::DIRECT: Direct position command,
- MotionMode::INTERPOLATE: interpolated movement or
- MotionMode::PLAN: path planning.
- pose_is_relative: If this is true the pose is interpreted as relative to the current pose.
- frame_id: The frame ID of a cartesian pose used for tf. The default is „arm_link_0“, but e.g. „gripper_tip“ might also be useful in some situations.
- interpolation_mode: This parameter is only needed for predefined poses and interpolated movements. The interpolation mode can be
- InterpolationMode::JOINTSPACE,
- InterpolationMode::CYLINDRIC or
- InterpolationMode.:CARTESIAN.
###Motion Mode
Three movement modes are available.
####Direct Position Command
In this mode only the goal position is set as position command. No interpolation or trajectory planning is done. This mode only works if the ramp generator of the motor controllers is enabled (the parameter can be set in luh_youbot_controller). Enabling the ramp generator is discouraged however because it significantly reduces the performance of other motion modes. Advantages: fast movement Disadvantages: unpredictable trajectory; doesn't work together with other motion modes
####Interpolated movement
In this mode the trajectory between start and goal point is interpolated in the specified coordinate system. In case of jointspace coordinates this means that the movement of all joints is synchronized which leads to a smoother trajectory and thereby to a better predictability of the movement. In cartesian coordinates the endeffector will be moved along a straight line. Cylindrical coordinates are somewhere in between but closer to cartesian. Advantages: good predictability of trajectory, precise movement possible Disadvantages: in case of cartesian or cylindrical coordinates only useful for small movements, no collision avoidance
####Path Planning
The path planning mode uses a set of predefined poses and neighborhood relations between these poses to compute a save trajectory from a start pose to a goal pose. This is the preferred motion mode for large movements of the arm. There is a default configuration which works for many use cases. However performance can be improved by a custom configuration tailored for a specific application. For details see: custom path planning configuration. Advantages: collisions can be avoided Disadvantages: slower than interpolation, might need some additional configuration
###Movement Execution
The moveToPose() method starts the movement action and returns immediately. While the action is executing you have several options.
You can abort the action at any time:
arm.abortCurrentAction();
You can check if the action is still being executed:
if(arm.isBusy()) //...
Or you can wait for the action to finish with a specified timeout. The default timeout is zero which means no timeout and the method will only return if the action finishes. The method returns true if the action has finished before the timeout.
// no timeout
arm.waitForCurrentAction();
// or 10 seconds timeout
if(!arm.waitForCurrentAction(10)) //...
You can e.g. wait for five seconds and abort the action if it has not finished.
if(!arm.waitForCurrentAction(5))
arm.abortCurrentAction();
When the action has finished you can check the status. The method actionSucceeded() returns true if the action has succeeded which means the arm has reached the desired goal position. In case anything went wrong during the execution the method will return false.
if(arm.actionSucceeded()) //...
###Velocity Commands
Velocity commands can be sent with a normal ROS publisher. The message types are:
- luh_youbot_msgs/JointVector
- luh_youbot_msgs/CartesianVector
- luh_youbot_msgs/CylindricVector
And the topics are:
- /arm_1/joint_velocity
- /arm_1/cartesian_velocity
- /arm_1/cylindric_velocity