Abstract class of an object that produces a ChppRobotMotion through a method ChppGikRobotTask::solve() More...
#include <hpp/gik/task/robot-task.hh>
Public Member Functions | |
ChppGikRobotTask (ChppGikStandingRobot *inStandingRobot, double inSamplingPeriod, const char *inTaskName) | |
Constructor. | |
bool | solve () |
Solve for joint motion. | |
void | showResolutionTime (bool inSwitch) |
show the resolution time | |
ChppRobotMotion & | solutionMotion () const |
Get the computed solution motion. | |
virtual void | bringBackZMP (bool inChoice, double inStartTime, double inDuration)=0 |
Option to bring back the ZMP before any other motion (Disabled by default). | |
virtual | ~ChppGikRobotTask () |
destructor | |
Protected Member Functions | |
void | cleanUp () |
Delete objects created in this instance. | |
virtual bool | algorithmSolve ()=0 |
The algorithm implemented by solve() | |
void | backupRobot () |
Backup current robot configuration (q, dot q, ddot q) | |
void | restoreRobot () |
Restore saved robot configuration (q, dot q, ddot q) and compute forward kinematics. | |
void | cropMotion (ChppGikRobotTask *inRobotTask) |
concatanate a task solution motion to the current attSolutionMotion and apply the last solution configuration to the robot. | |
Protected Attributes | |
ChppGikStandingRobot * | attStandingRobot |
Associated robot. | |
double | attSamplingPeriod |
Motion sampling period and its half. | |
double | attEps |
double | attStartTime |
Start time. | |
bool | attShowTime |
option to show resolution time | |
ChppRobotMotion * | attSolutionMotion |
The solution joint motion. | |
std::string | attTaskName |
This task's name. | |
CjrlRobotConfiguration | attInitialConfiguration |
Backup of robot configuration before task solving {@. | |
struct timeval * | Tps |
timimg {@ | |
struct timeval * | Tpf |
struct timezone * | Tzp |
Abstract class of an object that produces a ChppRobotMotion through a method ChppGikRobotTask::solve()
ChppGikRobotTask::ChppGikRobotTask | ( | ChppGikStandingRobot * | inStandingRobot, |
double | inSamplingPeriod, | ||
const char * | inTaskName | ||
) |
Constructor.
virtual ChppGikRobotTask::~ChppGikRobotTask | ( | ) | [inline, virtual] |
destructor
virtual bool ChppGikRobotTask::algorithmSolve | ( | ) | [protected, pure virtual] |
The algorithm implemented by solve()
Implemented in ChppGikWholeBodyTask, ChppGikReachTask, ChppGikHandTask, ChppGikStepBackTask, ChppGikMetaTask, ChppGikStepTask, and ChppGikHalfSittingTask.
void ChppGikRobotTask::backupRobot | ( | ) | [protected] |
Backup current robot configuration (q, dot q, ddot q)
virtual void ChppGikRobotTask::bringBackZMP | ( | bool | inChoice, |
double | inStartTime, | ||
double | inDuration | ||
) | [pure virtual] |
Option to bring back the ZMP before any other motion (Disabled by default).
A motion is planned to bring back the ZMP to the closest point on the line segment defining the center of the safe zone. The start time and the duration of this ZMP motion is left up to the user. The start time is defined relatively to the start of the locomotion plan. Example: bringBackZmp(-0.5, 2.0 ) will make the zmp planning start 0.5 seconds before the first locomotion element (if none, absolute time 0.0s), and take 2.0 seconds to finish. USE AT YOUR OWN RISK
Implemented in ChppGikWholeBodyTask, ChppGikGenericTask, ChppGikReachTask, ChppGikHandTask, ChppGikStepBackTask, ChppGikStepTask, ChppGikMetaTask, and ChppGikHalfSittingTask.
void ChppGikRobotTask::cleanUp | ( | ) | [protected] |
Delete objects created in this instance.
Meant to be called by derived classes'destructors
void ChppGikRobotTask::cropMotion | ( | ChppGikRobotTask * | inRobotTask | ) | [protected] |
concatanate a task solution motion to the current attSolutionMotion and apply the last solution configuration to the robot.
void ChppGikRobotTask::restoreRobot | ( | ) | [protected] |
Restore saved robot configuration (q, dot q, ddot q) and compute forward kinematics.
void ChppGikRobotTask::showResolutionTime | ( | bool | inSwitch | ) |
show the resolution time
ChppRobotMotion& ChppGikRobotTask::solutionMotion | ( | ) | const |
Get the computed solution motion.
Can be empty.
bool ChppGikRobotTask::solve | ( | ) |
Solve for joint motion.
Note that this method should return true in the case the task is already solved. It is up to the user to verify that the retrieved solutionMotion() is not an empty motion.
double ChppGikRobotTask::attEps [protected] |
Backup of robot configuration before task solving {@.
double ChppGikRobotTask::attSamplingPeriod [protected] |
Motion sampling period and its half.
bool ChppGikRobotTask::attShowTime [protected] |
option to show resolution time
ChppRobotMotion* ChppGikRobotTask::attSolutionMotion [protected] |
The solution joint motion.
ChppGikStandingRobot* ChppGikRobotTask::attStandingRobot [protected] |
Associated robot.
double ChppGikRobotTask::attStartTime [protected] |
Start time.
std::string ChppGikRobotTask::attTaskName [protected] |
This task's name.
struct timeval * ChppGikRobotTask::Tpf [protected] |
struct timeval* ChppGikRobotTask::Tps [protected] |
timimg {@
struct timezone* ChppGikRobotTask::Tzp [protected] |