#include "tutsim.hpp"
#include <opspace/Task.hpp>
#include <jspace/test/sai_util.hpp>
#include <boost/shared_ptr.hpp>
#include <err.h>
Go to the source code of this file.
Namespaces | |
namespace | tut04 |
Classes | |
class | tut04::JTask |
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 < tut04::JTask > | jtask |
Demonstration of inertial decoupling and Coriolis/centrifugal compensation. This tutorial uses a joint-space task which always uses gravity compensation, but the terms for inertial decoupling and Coriolis/centrifugal compensation can be switched on and off at runtime. When you start the demo, it tries to track a joint-space trajectory using a PD controller. When you hit Toggle, it switches on the inertia decoupling (desired torques get pre-multiplied by the joint-space mass-inertia matrix). After clicking Toggle a second time, it also adds the predicted Coriolis/centrifugal terms. As usual, after that the Toggle cycle repeats.
Definition in file tut04_inertia_coriolis.cpp.
static void draw_cb | ( | double | x0, | |
double | y0, | |||
double | scale | |||
) | [static] |
Definition at line 238 of file tut04_inertia_coriolis.cpp.
References tutsim::draw_robot(), and jtask.
int main | ( | int | argc, | |
char ** | argv | |||
) |
Definition at line 246 of file tut04_inertia_coriolis.cpp.
References draw_cb, jtask, model, model_filename(), 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 157 of file tut04_inertia_coriolis.cpp.
References jtask, model, jspace::State::position_, jspace::pretty_print(), and jspace::State::velocity_.
boost::shared_ptr<tut04::JTask> jtask [static] |
Definition at line 154 of file tut04_inertia_coriolis.cpp.
boost::shared_ptr<jspace::Model> model [static] |
Definition at line 153 of file tut04_inertia_coriolis.cpp.