#include "tutsim.hpp"
#include <opspace/task_library.hpp>
#include <jspace/test/sai_util.hpp>
#include <boost/shared_ptr.hpp>
#include <FL/fl_draw.H>
#include <err.h>
Go to the source code of this file.
Namespaces | |
namespace | tut05 |
Classes | |
class | tut05::PTask |
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 tut05::PTask | ptask |
static opspace::Parameter * | goalpos |
static opspace::Parameter * | goalvel |
static size_t | mode |
This tutorial, shows how to create an operational space task with reflected parameters. The task space is the plane, and the two parameters are the planar position and velocity of the end-effector, and the task-space servo is implemented in tut05::PTask by subclassing opspace::Task. The two parameters that get reflected are tut05::PTask::goalpos_ and tut05::PTask::goalvel_, and the reflection is achieved with calls to opspace::ParameterReflection::declareParameter() within the constructor of tut05::PTask.
When the simulation starts, the robot follows the usual swaying motion by re-initializing the simulation at each tick. After pressing Toggle, the planar task is used to track a goal point which is continuously moving around the plane. Initially, the raw J^T*F_op torque is used, without any compensation for gravity or dynamic effects, which leads to very poor tracking performance. Clicking Toggle a second time switches on gravity compensation, which makes the robot sag less. After a third click on Toggle, full inertial and Coriolis compensation is enabled, which leads to better performance. After pressing Toggle again, the cycle continues.
Note that the planar operational task has two dimensions, and given that the simulated robot has four degrees of freedom, this means that two degrees of redundancy remain. This is evidenced by the behavior of the robot, which keeps swinging around in the nullspace of the task. This undetermined nullspace motion leads to undesired effects on the tracking of the planar goal. In order to get rid of these disturbances, we need to add a well-defined control in the task nullspace, which is done in the tut06_eepos.cpp tutorial.
Definition in file tut05_opspace_and_parameters.cpp.
static void draw_cb | ( | double | x0, | |
double | y0, | |||
double | scale | |||
) | [static] |
Definition at line 285 of file tut05_opspace_and_parameters.cpp.
References opspace::Parameter::getVector(), and mode.
int main | ( | int | argc, | |
char ** | argv | |||
) |
Definition at line 319 of file tut05_opspace_and_parameters.cpp.
References draw_cb, opspace::ParameterReflection::lookupParameter(), model, model_filename(), opspace::PARAMETER_TYPE_VECTOR, tutsim::run(), servo_cb, and tutsim::set_draw_cb().
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 179 of file tut05_opspace_and_parameters.cpp.
References opspace::Task::actual_, tut05::PTask::curvel_, opspace::Task::getCommand(), opspace::Task::getJacobian(), tut05::PTask::goalpos_, tut05::PTask::goalvel_, tut05::PTask::init(), opspace::Task::jacobian_, mode, model, jspace::State::position_, jspace::pretty_print(), opspace::Parameter::set(), tut05::PTask::update(), and jspace::State::velocity_.
opspace::Parameter* goalpos [static] |
Definition at line 174 of file tut05_opspace_and_parameters.cpp.
opspace::Parameter* goalvel [static] |
Definition at line 175 of file tut05_opspace_and_parameters.cpp.
size_t mode [static] |
Definition at line 176 of file tut05_opspace_and_parameters.cpp.
Referenced by draw_cb(), and servo_cb().
boost::shared_ptr<jspace::Model> model [static] |
Definition at line 172 of file tut05_opspace_and_parameters.cpp.
tut05::PTask ptask [static] |
Definition at line 173 of file tut05_opspace_and_parameters.cpp.