ChppGikRobotTask Class Referenceabstract

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:

Public Member Functions

 ChppGikRobotTask (ChppGikStandingRobot *inStandingRobot, double inSamplingPeriod, const char *inTaskName)
 Constructor. More...
 
bool solve ()
 Solve for joint motion. More...
 
void showResolutionTime (bool inSwitch)
 show the resolution time More...
 
ChppRobotMotionsolutionMotion () const
 Get the computed solution motion. More...
 
virtual void bringBackZMP (bool inChoice, double inStartTime, double inDuration)=0
 Option to bring back the ZMP before any other motion (Disabled by default). More...
 
virtual ~ChppGikRobotTask ()
 destructor More...
 

Protected Member Functions

void cleanUp ()
 Delete objects created in this instance. More...
 
virtual bool algorithmSolve ()=0
 The algorithm implemented by solve() More...
 
void backupRobot ()
 Backup current robot configuration (q, dot q, ddot q) More...
 
void restoreRobot ()
 Restore saved robot configuration (q, dot q, ddot q) and compute forward kinematics. More...
 
void cropMotion (ChppGikRobotTask *inRobotTask)
 concatanate a task solution motion to the current attSolutionMotion and apply the last solution configuration to the robot. More...
 

Protected Attributes

ChppGikStandingRobotattStandingRobot
 Associated robot. More...
 
double attSamplingPeriod
 Motion sampling period and its half. More...
 
double attEps
 
double attStartTime
 Start time. More...
 
bool attShowTime
 option to show resolution time More...
 
ChppRobotMotionattSolutionMotion
 The solution joint motion. More...
 
std::string attTaskName
 This task's name. More...
 
CjrlRobotConfiguration attInitialConfiguration
 Backup of robot configuration before task solving {. More...
 
struct timeval * Tps
 timimg {@ More...
 
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::ChppGikRobotTask ( ChppGikStandingRobot inStandingRobot,
double  inSamplingPeriod,
const char *  inTaskName 
)

Constructor.

◆ ~ChppGikRobotTask()

virtual ChppGikRobotTask::~ChppGikRobotTask ( )
inlinevirtual

Member Function Documentation

◆ algorithmSolve()

virtual bool ChppGikRobotTask::algorithmSolve ( )
protectedpure virtual

◆ backupRobot()

void ChppGikRobotTask::backupRobot ( )
protected

Backup current robot configuration (q, dot q, ddot q)

Referenced by ~ChppGikRobotTask().

◆ bringBackZMP()

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.

◆ cleanUp()

void ChppGikRobotTask::cleanUp ( )
protected

Delete objects created in this instance.

Meant to be called by derived classes'destructors

Referenced by ~ChppGikRobotTask().

◆ cropMotion()

void ChppGikRobotTask::cropMotion ( ChppGikRobotTask inRobotTask)
protected

concatanate a task solution motion to the current attSolutionMotion and apply the last solution configuration to the robot.

Referenced by ~ChppGikRobotTask().

◆ restoreRobot()

void ChppGikRobotTask::restoreRobot ( )
protected

Restore saved robot configuration (q, dot q, ddot q) and compute forward kinematics.

Referenced by ~ChppGikRobotTask().

◆ showResolutionTime()

void ChppGikRobotTask::showResolutionTime ( bool  inSwitch)

show the resolution time

◆ solutionMotion()

ChppRobotMotion& ChppGikRobotTask::solutionMotion ( ) const

Get the computed solution motion.

Can be empty.

◆ solve()

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

◆ attEps

double ChppGikRobotTask::attEps
protected

◆ attInitialConfiguration

CjrlRobotConfiguration ChppGikRobotTask::attInitialConfiguration
protected

Backup of robot configuration before task solving {.

◆ attSamplingPeriod

double ChppGikRobotTask::attSamplingPeriod
protected

Motion sampling period and its half.

◆ attShowTime

bool ChppGikRobotTask::attShowTime
protected

option to show resolution time

◆ attSolutionMotion

ChppRobotMotion* ChppGikRobotTask::attSolutionMotion
protected

The solution joint motion.

◆ attStandingRobot

ChppGikStandingRobot* ChppGikRobotTask::attStandingRobot
protected

Associated robot.

◆ attStartTime

double ChppGikRobotTask::attStartTime
protected

Start time.

◆ attTaskName

std::string ChppGikRobotTask::attTaskName
protected

This task's name.

◆ Tpf

struct timeval * ChppGikRobotTask::Tpf
protected

◆ Tps

struct timeval* ChppGikRobotTask::Tps
protected

timimg {@

◆ Tzp

struct timezone* ChppGikRobotTask::Tzp
protected