tutorials/tut06_eepos.cpp File Reference

Author:
Roland Philippsen
More...

#include "tutsim.hpp"
#include <opspace/task_library.hpp>
#include <opspace/skill_library.hpp>
#include <opspace/ClassicTaskPostureController.hpp>
#include <jspace/test/sai_util.hpp>
#include <boost/shared_ptr.hpp>
#include <FL/fl_draw.H>
#include <err.h>

Include dependency graph for tut06_eepos.cpp:

Go to the source code of this file.

Functions

static std::string model_filename (TUTROB_XML_PATH_STR)
static bool servo_cb (size_t toggle_count, double wall_time_ms, double sim_time_ms, jspace::State &state, jspace::Vector &command)
static void draw_cb (double x0, double y0, double scale)
int main (int argc, char **argv)

Variables

static boost::shared_ptr
< jspace::Model
model
static boost::shared_ptr
< opspace::ClassicTaskPostureController
controller
static boost::shared_ptr
< opspace::GenericSkill
skill
static boost::shared_ptr
< opspace::CartPosTask
eetask
static boost::shared_ptr
< opspace::JPosTask
jtask
static opspace::Parametereegoalpos
static opspace::Parametereegoalvel
static opspace::Parameterjgoalpos
static opspace::Parameterjgoalvel
static size_t mode


Detailed Description

Author:
Roland Philippsen

This tutorial shows Cartesian trajectory tracking task with a controller joint posture in the nullspace of the task. It shows how to implement this behavior with opspace::Task subclasses from the provided task library, and by relying on the provided opspace::ClassicTaskPostureController to perform the dynamically consistent nullspace projection. It also introduces the concept of opspace::Skill, which provides a container for task hierarchies. For this example, we simply use the opspace::GenericSkill.

As usual, when the simulation starts, it is in swaying-reinitialization mode. After clicking Toggle once, the robot holds the current position in Cartesian as well as joint space. Clicking Toggle a second time starts a swaying joint-space motion in the nullspace of the task: the robot will attempt to minimize the difference between the actual and desired joint angles, without moving the position of the end-effector point. Clicking Toggle again enters Cartesian trajectory tracking mode with a constant joint posture, and clicking Toggle a fourth time makes the posture change continously while tracking the trajectory.

Definition in file tut06_eepos.cpp.


Function Documentation

static void draw_cb ( double  x0,
double  y0,
double  scale 
) [static]

Definition at line 167 of file tut06_eepos.cpp.

References tutsim::draw_delta_jpos(), opspace::Parameter::getVector(), and mode.

Here is the call graph for this function:

int main ( int  argc,
char **  argv 
)

Definition at line 201 of file tut06_eepos.cpp.

References controller, draw_cb, eetask, jtask, model, model_filename(), opspace::PARAMETER_TYPE_VECTOR, tutsim::run(), servo_cb, tutsim::set_draw_cb(), and skill.

Here is the call graph for this function:

static std::string model_filename ( TUTROB_XML_PATH_STR   )  [static]

static bool servo_cb ( size_t  toggle_count,
double  wall_time_ms,
double  sim_time_ms,
jspace::State state,
jspace::Vector command 
) [static]

Definition at line 73 of file tut06_eepos.cpp.

References controller, mode, model, jspace::State::position_, opspace::Parameter::set(), skill, and jspace::State::velocity_.

Here is the call graph for this function:


Variable Documentation

boost::shared_ptr<opspace::ClassicTaskPostureController> controller [static]

Definition at line 62 of file tut06_eepos.cpp.

Referenced by main(), and servo_cb().

opspace::Parameter* eegoalpos [static]

Definition at line 66 of file tut06_eepos.cpp.

opspace::Parameter* eegoalvel [static]

Definition at line 67 of file tut06_eepos.cpp.

boost::shared_ptr<opspace::CartPosTask> eetask [static]

Definition at line 64 of file tut06_eepos.cpp.

Referenced by main().

opspace::Parameter* jgoalpos [static]

Definition at line 68 of file tut06_eepos.cpp.

opspace::Parameter* jgoalvel [static]

Definition at line 69 of file tut06_eepos.cpp.

boost::shared_ptr<opspace::JPosTask> jtask [static]

Definition at line 65 of file tut06_eepos.cpp.

size_t mode [static]

Definition at line 70 of file tut06_eepos.cpp.

boost::shared_ptr<jspace::Model> model [static]

Definition at line 61 of file tut06_eepos.cpp.

boost::shared_ptr<opspace::GenericSkill> skill [static]

Definition at line 63 of file tut06_eepos.cpp.

Referenced by main(), and servo_cb().


Generated on Fri Aug 26 01:32:10 2011 for Stanford Whole-Body Control Framework by  doxygen 1.5.4