SCL Tutorial 1

scl.git/tutorial/scl_tutorial1_xml_kinematics_dynamics/

Terminal output: Result of computing robot kinematics, inertia tensor, gravity force, and a hand Jacobian

Goal : Specify robot using an xml file and compute dynamics

This tutorial aims to introduce you to SCL's file format and show you how to write compact and clean code.

Step 0 : Compile and run tutorial

We already showed you how to do this in Tutorial 0. So please refresh your memory! :-). Note that we will stop talking about the basic steps as we advance through the tutorial.

Step 1 : Look at the xml file (RRRCfg.xml)

The file contains a robot and a robot-spec. The "robot" is an instance of a "robot-spec". So if you want two robots of a similar kind, you don't need to write duplicate xml code. Read through the xml file. It should be self explanatory. It merely specifies the kinematic tree corresponding to the robot, which we now know is an RRR (revolute-revolute-revolute) robot.

     < robot name="rrrbot"> 
        < gravity>0.000   0.000   -9.81< /gravity> 
        < spec>RRR< /spec>
        < file>./RRRCfg.xml< /file>
        < root_link>
            < link_name>root< /link_name>
            < position_in_parent>0 0 0< /position_in_parent> 
            < orientation_in_parent>0 0 0 1< /orientation_in_parent>
        < /root_link>
    < /robot>
    
    
    < robot spec_name="RRR"> 
	      < link>
		      < link_name>link_0< /link_name> < !--unique link name -->
		      < position_in_parent>0 0 0< /position_in_parent> < !--xyz in parent frame -->
		      < orientation_in_parent>0 0 0 1< /orientation_in_parent> < !-- xyz w quaternion in parent frame -->
		      < mass>1.0< /mass> < !-- Of the link, in kgs. -->
		      < inertia>1 1 1< /inertia> < !-- Ixx Iyy Izz at the center of mass -->
		      < center_of_mass>0 0 -0.1< /center_of_mass> < !-- xyz -->
		      < joint_name>q0-rot-y< /joint_name> < !-- unique joint name. -->
		      < parent_link_name>root< /parent_link_name> < !-- The parent link. Ground is fixed. -->
		      < joint_type>ry< /joint_type> < !-- The type of joint. (p)rismatic/(r)evolute + x/y/z (axis) -->
		      < joint_limits>-3.141590 3.141590< /joint_limits> < !-- Minimum and maximum joint coordinate values -->
		      < default_joint_position>1.0< /default_joint_position> < !-- Initial configuration -->
	      < /link>
    < !-- And so on ... -->

Step 2 : Initialize various classes

SCL requires properly initialized data structures. While some values might not seem particularly useful for your specific program, they might be used by some background code. In particular, there are extensive checks everywhere to make sure that data structures have a string name, a type, and have been initialized properly. Note that SCL supports dynamic typing (for more information see the test application in 3rdparty/sUtil).

Step 3 : Compute the generalized coordinate model (kinematics and dynamics)

To make life easy, SCL collects all kinematics and dynamics computations and caches them in a data structure that can be used by the physics, graphics, or control code.

 // Compute dynamics.
 dyn_scl.computeGCModel(&rio.sensors_,&rgcm);

Step 4 : Iterate over the the dynamic tree

Computing the generalized coordinate model (the GCmodel) ensures that the dynamic tree has all the latest kinematic transformations and dynamic quantities. One may efficiently iterate over the tree using standard c++ iterators. The standard tree structure is provided by the data structure "3rdparty/sUtil" library.

 sutil::CMappedTree::const_iterator it,ite;
 for(it = rgcm.rbdyn_tree_.begin(), ite = rgcm.rbdyn_tree_.end(); it!=ite; ++it)
 { std::cout<<"\n\nLink:"<name_<<"\npar_T_link\n"<<(it->T_lnk_.matrix())<<"\nJcom\n"<<(it->J_com_);  }

Step 5 : Print dynamic estimates

We're done. The remaining code just prints stuff. Notice how it is more compact than Tutorial 0. This should convince you that it is good to use configuration files instead of specifying stuff in code. Moreover, if you use files, you don't have to recompile each and every time you change something.


References and Links

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




Assignment


Q1 : Map joint space into cartesian space

Take the RPR robot you created in the previous assignment. You will now study its kinematics in more detail.

(a) Set the first revolute and the prismatic joint to random values drawn between (-pi, pi). Plot the end-effector position while setting the third revolute joint to values [-pi:0.1:pi].

(b) Set third revolute and the prismatic joint to random values drawn between (-pi, pi). Plot the end-effector position while setting the first revolute joint to values [-pi:0.1:pi].


Q2 : Inverse kinematics and task redundancy

Now your goal is to make sure the robot moves in the x-y plane.

(a) Specify two random reachable points in the x-y plane and solve for the joint angle values at each point. Remember that the z position may be arbitrary. (Any z-value in your solution will do).
You now have two sets of generalized coordinates (joint angles), qa & qb.

(b) Take your solution generalized coordinates, qa and qb, and linearly interpolate q between qa and qb and plot the resulting end-effector positions.
Does the hand move in a straight line?
Discuss the pros and cons of using this approach to move a real robot.

(Review) The above method is called "inverse kinematics", and is commonly used in joint-space control to generate robot motion trajectories. However, it is usually complicated and often induces complex sinusoidal motions at the end-effector. Future tutorials will introduce methods to address this problem.




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