#include <Task.hpp>
Public Member Functions | |
virtual Status | init (Model const &model)=0 |
Abstract, implemented by subclasses in order to initialize the task. | |
virtual Status | update (Model const &model)=0 |
Abstract, implemented by subclasses in order to compute the current task state, the command acceleration, and the Jacobian. | |
Vector const & | getActual () const |
| |
Vector const & | getCommand () const |
| |
Matrix const & | getJacobian () const |
| |
double | getSigmaThreshold () const |
SVD cutoff value for pseudo inverse, exists in all tasks because Controller implementations need it. | |
virtual void | dump (std::ostream &os, std::string const &title, std::string const &prefix) const |
virtual void | dbg (std::ostream &os, std::string const &title, std::string const &prefix) const |
Protected Member Functions | |
Task (std::string const &name) | |
Protected Attributes | |
Vector | actual_ |
Vector | command_ |
Matrix | jacobian_ |
double | sigma_threshold_ |
Parameter "sigma_threshold", SVD cutoff value for pseudo inverse. |
The base class provides parameter introspection facilities and an interface that is used by opspace::Controller instances to come up with control signals for a robot.
This is one of the most important classes in the opspace namespace. You implement tasks by subclassing from it (or one of its more specialized derivatives) and implementing the init() and update() methods. You can also override some other methods if you are not happy with the defaults.
A simple but complete example of concrete Task subclass would look like this:
class Thermostat : public Task { public: Thermostat(std::string const & name) : Task(name), temp_(0) { declareParameter("desired_temperature", &temp_); } virtual Status init(Model const & model) { if (1 != model.getNDOF()) { return Status(false, "are you sure this is a fridge?"); } jacobian_ = Vector::Ones(1); // somewhat spurious in this example command_ = Vector::Zero(1); return update(model); } virtual Status update(Model const & model) { actual_ = model.getState().position_; if (actual_[0] > temp_) { command_[0] = 1; } else { command_[0] = 0; } // jacobian_ was set in init() and never changes in this example Status ok; return ok; } private: double temp_; };
Definition at line 88 of file Task.hpp.
opspace::Task::Task | ( | std::string const & | name | ) | [explicit, protected] |
Definition at line 34 of file Task.cpp.
References actual_, command_, opspace::ParameterReflection::declareParameter(), and sigma_threshold_.
Abstract, implemented by subclasses in order to initialize the task.
This is important for stateful tasks, for instance in order to initialize a trajectory-following behavior. The init() method also gets called when tasks are switched at runtime, so subclasses should NOT assume that init() only gets called once at startup.
Implemented in opspace::DraftPIDTask, opspace::CartPosTask, opspace::JPosTask, opspace::SelectedJointPostureTask, opspace::CartPosTrjTask, opspace::JPosTrjTask, opspace::JointLimitTask, opspace::OrientationTask, tut02::JTask, tut03::JTask, tut04::JTask, and tut05::PTask.
Abstract, implemented by subclasses in order to compute the current task state, the command acceleration, and the Jacobian.
Given the current joint-space model passed as argument to this method, subclasses have to set the actual_, command_, and jacobian_ fields. These will then get retrieved according to the task hierarchy and assembled into joint torque commands using dynamically consistent nullspace projection.
Implemented in opspace::DraftPIDTask, opspace::CartPosTask, opspace::JPosTask, opspace::SelectedJointPostureTask, opspace::CartPosTrjTask, opspace::JPosTrjTask, opspace::JointLimitTask, opspace::OrientationTask, tut02::JTask, tut03::JTask, tut04::JTask, and tut05::PTask.
Vector const& opspace::Task::getActual | ( | ) | const [inline] |
Vector const& opspace::Task::getCommand | ( | ) | const [inline] |
In the operational space formulation, this is simply the desired acceleration of the task point (in task space, of course). Reminder: command_ must be set by subclasses in their update() method.
Definition at line 132 of file Task.hpp.
References command_.
Referenced by opspace::ClassicTaskPostureController::computeCommand(), and servo_cb().
Matrix const& opspace::Task::getJacobian | ( | ) | const [inline] |
The Jacobian maps joint velocities to task space velocities (it thus has M rows and N columns, where M is the dimension of the task space and N the number of degrees of freedom of the robot). Usually, the Jacobian is configuration dependent and is updated along with the command in the update() method. Some tasks, however, have simple and constant Jacobians which can be set in the init() method. The Jacobian is used by the opspace::Controller to compensate for rigid body dynamics and to decouple tasks according to a strict hierarchy. Reminder: jacobian_ must be set by subclasses in their update() method.
Definition at line 147 of file Task.hpp.
References jacobian_.
Referenced by opspace::ClassicTaskPostureController::computeCommand(), and servo_cb().
double opspace::Task::getSigmaThreshold | ( | ) | const [inline] |
SVD cutoff value for pseudo inverse, exists in all tasks because Controller implementations need it.
Definition at line 153 of file Task.hpp.
References sigma_threshold_.
Referenced by opspace::TaskPostureTrjSkill::checkJStarSV(), opspace::TaskPostureSkill::checkJStarSV(), and opspace::ClassicTaskPostureController::computeCommand().
void opspace::Task::dump | ( | std::ostream & | os, | |
std::string const & | title, | |||
std::string const & | prefix | |||
) | const [virtual] |
Reimplemented from opspace::ParameterReflection.
Definition at line 48 of file Task.cpp.
References actual_, command_, opspace::ParameterReflection::dump(), opspace::ParameterReflection::instance_name_, jacobian_, and jspace::pretty_print().
void opspace::Task::dbg | ( | std::ostream & | os, | |
std::string const & | title, | |||
std::string const & | prefix | |||
) | const [virtual] |
Reimplemented in opspace::DraftPIDTask, opspace::TrajectoryTask, opspace::JointLimitTask, and opspace::OrientationTask.
Vector opspace::Task::actual_ [protected] |
Definition at line 164 of file Task.hpp.
Referenced by opspace::JointLimitTask::dbg(), opspace::TrajectoryTask::dbg(), dump(), getActual(), tut05::PTask::init(), opspace::JPosTrjTask::init(), opspace::CartPosTrjTask::init(), opspace::SelectedJointPostureTask::init(), opspace::JPosTask::init(), opspace::CartPosTask::init(), opspace::DraftPIDTask::init(), servo_cb(), Task(), tut05::PTask::update(), tut04::JTask::update(), tut03::JTask::update(), tut02::JTask::update(), opspace::JointLimitTask::update(), opspace::JPosTrjTask::update(), opspace::CartPosTrjTask::update(), opspace::SelectedJointPostureTask::update(), opspace::JPosTask::update(), opspace::CartPosTask::update(), opspace::DraftPIDTask::update(), opspace::OrientationTask::updateActual(), opspace::CartPosTrjTask::updateActual(), opspace::CartPosTask::updateActual(), opspace::JointLimitTask::updateState(), and tut05::PTask::updateStateAndJacobian().
Vector opspace::Task::command_ [protected] |
Definition at line 165 of file Task.hpp.
Referenced by opspace::OrientationTask::dbg(), dump(), getCommand(), opspace::SelectedJointPostureTask::init(), Task(), tut05::PTask::update(), tut04::JTask::update(), tut03::JTask::update(), tut02::JTask::update(), opspace::OrientationTask::update(), opspace::JointLimitTask::update(), opspace::JPosTrjTask::update(), opspace::CartPosTrjTask::update(), opspace::SelectedJointPostureTask::update(), opspace::JPosTask::update(), opspace::CartPosTask::update(), and opspace::DraftPIDTask::update().
Matrix opspace::Task::jacobian_ [protected] |
Definition at line 166 of file Task.hpp.
Referenced by opspace::JointLimitTask::dbg(), dump(), getJacobian(), tut04::JTask::init(), tut03::JTask::init(), tut02::JTask::init(), opspace::JointLimitTask::init(), opspace::JPosTrjTask::init(), opspace::SelectedJointPostureTask::init(), opspace::JPosTask::init(), opspace::DraftPIDTask::init(), servo_cb(), opspace::JointLimitTask::update(), opspace::CartPosTrjTask::update(), opspace::CartPosTask::update(), opspace::OrientationTask::updateActual(), opspace::JointLimitTask::updateState(), and tut05::PTask::updateStateAndJacobian().
double opspace::Task::sigma_threshold_ [protected] |
Parameter "sigma_threshold", SVD cutoff value for pseudo inverse.
Exists in all tasks because Controller implementations need it.
Definition at line 171 of file Task.hpp.
Referenced by getSigmaThreshold(), and Task().