ChppGikRobotTask Class Reference

Abstract class of an object that produces a ChppRobotMotion through a method ChppGikRobotTask::solve() More...

#include <hpp/gik/task/robot-task.hh>

Inheritance diagram for ChppGikRobotTask:
Collaboration diagram for ChppGikRobotTask:

List of all members.

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
ChppRobotMotionsolutionMotion () 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

ChppGikStandingRobotattStandingRobot
 Associated robot.
double attSamplingPeriod
 Motion sampling period and its half.
double attEps
double attStartTime
 Start time.
bool attShowTime
 option to show resolution time
ChppRobotMotionattSolutionMotion
 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

Detailed Description

Abstract class of an object that produces a ChppRobotMotion through a method ChppGikRobotTask::solve()


Constructor & Destructor Documentation

ChppGikRobotTask::ChppGikRobotTask ( ChppGikStandingRobot inStandingRobot,
double  inSamplingPeriod,
const char *  inTaskName 
)

Constructor.

virtual ChppGikRobotTask::~ChppGikRobotTask ( ) [inline, virtual]

destructor


Member Function Documentation

virtual bool ChppGikRobotTask::algorithmSolve ( ) [protected, pure virtual]
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.


Member Data Documentation

double ChppGikRobotTask::attEps [protected]

Backup of robot configuration before task solving {@.

Motion sampling period and its half.

option to show resolution time

The solution joint motion.

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]