Public Member Functions | |
PTask () | |
void | updateStateAndJacobian (Model const &model) |
virtual jspace::Status | init (jspace::Model const &model) |
Abstract, implemented by subclasses in order to initialize the task. | |
virtual jspace::Status | update (jspace::Model const &model) |
Abstract, implemented by subclasses in order to compute the current task state, the command acceleration, and the Jacobian. | |
Public Attributes | |
bool | initialized_ |
double | kp_ |
double | kd_ |
jspace::Vector | curvel_ |
jspace::Vector | goalpos_ |
jspace::Vector | goalvel_ |
Definition at line 71 of file tut05_opspace_and_parameters.cpp.
tut05::PTask::PTask | ( | ) | [inline] |
Definition at line 73 of file tut05_opspace_and_parameters.cpp.
References opspace::ParameterReflection::declareParameter(), goalpos_, and goalvel_.
void tut05::PTask::updateStateAndJacobian | ( | Model const & | model | ) | [inline] |
Definition at line 81 of file tut05_opspace_and_parameters.cpp.
References opspace::Task::actual_, jspace::Model::computeGlobalFrame(), jspace::Model::computeJacobian(), curvel_, jspace::Model::getNode(), jspace::Model::getState(), opspace::Task::jacobian_, and jspace::State::velocity_.
Referenced by init(), and update().
virtual jspace::Status tut05::PTask::init | ( | jspace::Model const & | model | ) | [inline, virtual] |
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.
Implements opspace::Task.
Definition at line 96 of file tut05_opspace_and_parameters.cpp.
References opspace::Task::actual_, goalpos_, goalvel_, initialized_, kd_, kp_, and updateStateAndJacobian().
Referenced by servo_cb(), and update().
virtual jspace::Status tut05::PTask::update | ( | jspace::Model const & | model | ) | [inline, virtual] |
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.
Implements opspace::Task.
Definition at line 130 of file tut05_opspace_and_parameters.cpp.
References opspace::Task::actual_, opspace::Task::command_, curvel_, goalpos_, goalvel_, init(), initialized_, kd_, kp_, and updateStateAndJacobian().
Referenced by servo_cb().
Definition at line 157 of file tut05_opspace_and_parameters.cpp.
double tut05::PTask::kp_ |
Definition at line 158 of file tut05_opspace_and_parameters.cpp.
double tut05::PTask::kd_ |
Definition at line 158 of file tut05_opspace_and_parameters.cpp.
Definition at line 159 of file tut05_opspace_and_parameters.cpp.
Referenced by servo_cb(), update(), and updateStateAndJacobian().
Definition at line 160 of file tut05_opspace_and_parameters.cpp.
Referenced by init(), PTask(), servo_cb(), and update().
Definition at line 160 of file tut05_opspace_and_parameters.cpp.
Referenced by init(), PTask(), servo_cb(), and update().