SCL Tutorial 0

scl.git/tutorial/scl_tutorial0_setup_robot/

Terminal output: Result of computing robot kinematics

Goal : Specify robots using kinematic tree data structures

This tutorial aims to introduce you to SCL's data structures. You will learn how to specify robots. A robot is defined as an actuated articulated body. In plain English {robot = a set of rigid bodies connected by joints + some actuators}.


Step 0 : Compile and run tutorial

There is a README.txt file in the directory. Follow its instructions. In general, it is a good idea to always read the README.txt file before doing anything. For now, however, we'll run you through what to do. In the scl base dir:

 scl@unicorn:~/Code/scl.git$ cd tutorial/scl_tutorial0_setup_robot/
 scl@unicorn:~/Code/scl.git/tutorial/scl_tutorial0_setup_robot$ make release
 scl@unicorn:~/Code/scl.git/tutorial/scl_tutorial0_setup_robot$ ./scl_tutorial0_setup_robot

Step 1 : Specify a rigid body

The code starts off by setting the properties of different rigid bodies, and will then hook them up into a tree. For instance, this (slightly modified) code specifies one rigid body (or a link; or a node; whatever terminology works for you).

 scl::SRigidBody rb;    //A {rigid body, link, node} data structure
 rb.init();             //This resets the data structure so we can fill in values
 rb.link_id_ = -1;  rb.name_ = "root"; //(root starts at -1)
 rb.robot_name_ = rname;  rb.parent_name_ = "none";
 rb.joint_name_ = "none"; rb.joint_type_ = scl::JOINT_TYPE_NOTASSIGNED;
 rb.pos_in_parent_<<0,0,0;  rb.is_root_ = true;
 rds.rb_tree_.create(rb.name_,rb,true);

Step 2 : Specify all rigid bodies for a robot

The code then proceeds to specify the other rigid bodies and connects them into a tree based on the parent names specified. Each tree must have a root. The name, however, may be arbitrary. Eg. You can name the "root" node a "base", or "ground", or "pink unicorn from the heavens above". Note that string names in general have no associated meaning. You can always use arbitrary naming schemes (as long as you keep the scheme consistent across your code). The code then prints the robot tree (so you can be sure it was what you specified).

Step 3 : Specify rigid body ordering

Next the code sorts the nodes so that link0 has id0 etc.. This step is not necessary, but can reduce your cognitive burden later on as you program complex robots. Though if you want to make life difficult for yourself, you can randomize the order. ;-). SCL won't care but anytime you use a numeric id, you'll have to recall what order you specified. After sorting the link ids, the code prints the robot tree.

Step 4 : Link rigid bodies into a tree (create a robot)

The code then proceeds to specify the other rigid bodies and connects them into a tree based on the parent names specified. Each tree must have a root. The name, however, may be arbitrary. Eg. You can name the "root" node a "base", or "ground", or "pink unicorn from the heavens above". Note that string names in general have no associated meaning. You can always use arbitrary naming schemes (as long as you keep the scheme consistent across your code).

Step 5 : Create a dynamic tree

The code then creates a dynamic tree similar to the static kinematic tree above.

/** Question : Why do we use two trees?
 *  Answer   : For a robot, there is static and dynamic data. For instance, the link lengths don't change
 *  very often but the joint angles do. Separating both data types reduces the likelihood of errors
 *  in some dynamics code affecting the static structure. Dynamics data, however, always has access to
 *  a read-only copy of the static data.
 */

Step 6 : Initialize the dynamics class and compute kinematics

The code finally initializes the dynamics class (requires the static tree data structure) and prints the kinematics (see actual code).

  scl::CDynamicsScl dyn_scl;
  flag = dyn_scl.init(rds);
  if(false == flag) { std::cout<<"\nERROR : Could not initialize control & dynamics engine\n\n"; return 1;  }
  else  { std::cout<<"\n\n **** Progress : Initialized control & dynamics engine."; }

  // Let's compute some kinematic quantities with the dynamics object (depend on q,dq only, not on inertia etc.)
  dyn_scl.computeTransformsForAllLinks(rbd_tree, q);
  dyn_scl.computeJacobianComForAllLinks(rbd_tree, q);


References and Links

Operational Space Control Math Tutorial: 3-dof and 6-dof chain robots.



Assignment


Q1 : Specify a new robot and test kinematics

Following the tutorial's example, create a new RPR robot with suitable link lengths, masses, inertias etc. Compute the forward kinematics by hand for three random generalized coordinate vectors. Test that your hand-computed solutions give the same result as the code.
Make sure that your robot can move its end-effector in 3-D space (i.e., it should not be a planar robot).

(a) Write out the transformation matrix that you computed for your RPR robot (as a function of link lengths and joint coordinates).

(b) Compare the end-effector position for a variety of randomly selected generalized coordinate (joint angle/position) values using both your method and the modified tutorial code.


Q2 : What is the difference between a chain and a tree robot?

In general, it is feasible to specify robots as kinematic chains, trees, or even graphs. For now, the code supports chains and trees. In this particular tutorial, we used a chain.
Consider specifying a graph robot instead. Think of a humanoid robot with its hands clasped.

(a) How many constraints does a rigid loop connection create?

(Extra credit) What complexity did the loop induce? How would you represent the kinematic transformations in code? Outline a potential design for "kinematic representation only".




    © Samir Menon. CCA 3.0 license.
    Valid HTML and CSS.
    Last updated on Sep 2nd, 2014