dart
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
State Class Reference

class State More...

#include <State.hpp>

Collaboration diagram for State:
Collaboration graph
[legend]

Public Member Functions

 State (dart::dynamics::SkeletonPtr _skeleton, const std::string &_name)
 Constructor.
 
virtual ~State ()
 Destructor.
 
void setName (std::string &_name)
 Set name.
 
const std::string & getName () const
 Get name.
 
void setNextState (State *_nextState)
 Set next state.
 
void setTerminalCondition (TerminalCondition *_condition)
 Add terminal condition.
 
StategetNextState () const
 Get next state.
 
double getElapsedTime () const
 Get elapsed time.
 
void setDesiredJointPosition (const std::string &_jointName, double _val)
 Set desired joint position whose name is _jointName.
 
double getDesiredJointPosition (int _idx) const
 Get desired joint position whose index is _idx.
 
double getDesiredJointPosition (const std::string &_jointName) const
 Get desired joint position whose name is _jointName.
 
void setDesiredSwingLegGlobalAngleOnSagital (double _val)
 Set desired global angle swing leg on sagital plane.
 
void setDesiredSwingLegGlobalAngleOnCoronal (double _val)
 Set desired global angle swing leg on coronal plane.
 
void setDesiredPelvisGlobalAngleOnSagital (double _val)
 Set desired global angle pelvis on sagital plane.
 
void setDesiredPelvisGlobalAngleOnCoronal (double _val)
 Set desired global angle of pelvis on coronal plane.
 
void setProportionalGain (int _idx, double _val)
 Set proportional gain for PD controller.
 
void setProportionalGain (const std::string &_jointName, double _val)
 Set proportional gain for PD controller.
 
double getProportionalGain (int _idx) const
 Get proportional gain for PD controller.
 
double getProportionalGain (const std::string &_jointName) const
 Get proportional gain for PD controller.
 
void setDerivativeGain (int _idx, double _val)
 Set derivative gain for PD controller.
 
void setDerivativeGain (const std::string &_jointName, double _val)
 Set derivative gain for PD controller.
 
double getDerivativeGain (int _idx) const
 Get derivative gain for PD controller.
 
void setFeedbackSagitalCOMDistance (std::size_t _index, double _val)
 Set balance feedback gain parameter for sagital com distance.
 
void setFeedbackSagitalCOMVelocity (std::size_t _index, double _val)
 Set balance feedback gain parameter for sagital com velocity.
 
void setFeedbackCoronalCOMDistance (std::size_t _index, double _val)
 Set balance feedback gain parameter for sagital com distance.
 
void setFeedbackCoronalCOMVelocity (std::size_t _index, double _val)
 Set balance feedback gain parameter for sagital com velocity.
 
void setStanceFootToLeftFoot ()
 Set stance foot to left foot.
 
void setStanceFootToRightFoot ()
 Set stance foot to right foot.
 
virtual void begin (double _currentTime)
 Initiate state. More...
 
virtual void computeControlForce (double _timestep)
 Compute control force and apply it to Atlas robot.
 
virtual bool isTerminalConditionSatisfied () const
 Check if terminal condision is satisfied.
 
virtual void end (double _currentTime)
 Finalize state. More...
 
 State (dart::dynamics::SkeletonPtr _skeleton, const std::string &_name)
 Constructor.
 
virtual ~State ()
 Destructor.
 
void setName (std::string &_name)
 Set name.
 
const std::string & getName () const
 Get name.
 
void setNextState (State *_nextState)
 Set next state.
 
void setTerminalCondition (TerminalCondition *_condition)
 Add terminal condition.
 
StategetNextState () const
 Get next state.
 
double getElapsedTime () const
 Get elapsed time.
 
void setDesiredJointPosition (const std::string &_jointName, double _val)
 Set desired joint position whose name is _jointName.
 
double getDesiredJointPosition (int _idx) const
 Get desired joint position whose index is _idx.
 
double getDesiredJointPosition (const std::string &_jointName) const
 Get desired joint position whose name is _jointName.
 
void setDesiredSwingLegGlobalAngleOnSagital (double _val)
 Set desired global angle swing leg on sagital plane.
 
void setDesiredSwingLegGlobalAngleOnCoronal (double _val)
 Set desired global angle swing leg on coronal plane.
 
void setDesiredPelvisGlobalAngleOnSagital (double _val)
 Set desired global angle pelvis on sagital plane.
 
void setDesiredPelvisGlobalAngleOnCoronal (double _val)
 Set desired global angle of pelvis on coronal plane.
 
void setProportionalGain (int _idx, double _val)
 Set proportional gain for PD controller.
 
void setProportionalGain (const std::string &_jointName, double _val)
 Set proportional gain for PD controller.
 
double getProportionalGain (int _idx) const
 Get proportional gain for PD controller.
 
double getProportionalGain (const std::string &_jointName) const
 Get proportional gain for PD controller.
 
void setDerivativeGain (int _idx, double _val)
 Set derivative gain for PD controller.
 
void setDerivativeGain (const std::string &_jointName, double _val)
 Set derivative gain for PD controller.
 
double getDerivativeGain (int _idx) const
 Get derivative gain for PD controller.
 
void setFeedbackSagitalCOMDistance (std::size_t _index, double _val)
 Set balance feedback gain parameter for sagital com distance.
 
void setFeedbackSagitalCOMVelocity (std::size_t _index, double _val)
 Set balance feedback gain parameter for sagital com velocity.
 
void setFeedbackCoronalCOMDistance (std::size_t _index, double _val)
 Set balance feedback gain parameter for sagital com distance.
 
void setFeedbackCoronalCOMVelocity (std::size_t _index, double _val)
 Set balance feedback gain parameter for sagital com velocity.
 
void setStanceFootToLeftFoot ()
 Set stance foot to left foot.
 
void setStanceFootToRightFoot ()
 Set stance foot to right foot.
 
virtual void begin (double _currentTime)
 Initiate state. More...
 
virtual void computeControlForce (double _timestep)
 Compute control force and apply it to Atlas robot.
 
virtual bool isTerminalConditionSatisfied () const
 Check if terminal condision is satisfied.
 
virtual void end (double _currentTime)
 Finalize state. More...
 

Protected Member Functions

Eigen::Vector3d getCOM () const
 Get center of mass.
 
Eigen::Vector3d getCOMVelocity () const
 Get velocity of center of mass.
 
Eigen::Isometry3d getCOMFrame () const
 Get a frame such that: 1) The origin is at the COM 2) The z-axis is perpendicular to the ground (y-axis by default) 3) The x-axis is a projected x-axis of pelvis on to perpendicular plane against to the z-axis.
 
double getSagitalCOMDistance ()
 Get sagital com distance.
 
double getSagitalCOMVelocity ()
 Get sagital com velocity.
 
double getCoronalCOMDistance ()
 Get coronal com distance.
 
double getCoronalCOMVelocity ()
 Get coronal com velocity.
 
Eigen::Vector3d getStanceAnklePosition () const
 Get stance ankle position.
 
Eigen::Vector3d getLeftAnklePosition () const
 Get left ankle position.
 
Eigen::Vector3d getRightAnklePosition () const
 Get right ankle position.
 
double getSagitalPelvisAngle () const
 Get global pelvis upvector angle on sagital plane.
 
double getCoronalPelvisAngle () const
 Get global pelvis upvector angle on coronal plane.
 
double getSagitalLeftLegAngle () const
 Get global left leg angle on sagital plane.
 
double getSagitalRightLegAngle () const
 Get global right leg angle on sagital plane.
 
double getCoronalLeftLegAngle () const
 Get global left leg angle on coronal plane.
 
double getCoronalRightLegAngle () const
 Get global right leg angle on coronal plane.
 
Eigen::Vector3d getCOM () const
 Get center of mass.
 
Eigen::Vector3d getCOMVelocity () const
 Get velocity of center of mass.
 
Eigen::Isometry3d getCOMFrame () const
 Get a frame such that: 1) The origin is at the COM 2) The z-axis is perpendicular to the ground (y-axis by default) 3) The x-axis is a projected x-axis of pelvis on to perpendicular plane against to the z-axis.
 
double getSagitalCOMDistance ()
 Get sagital com distance.
 
double getSagitalCOMVelocity ()
 Get sagital com velocity.
 
double getCoronalCOMDistance ()
 Get coronal com distance.
 
double getCoronalCOMVelocity ()
 Get coronal com velocity.
 
Eigen::Vector3d getStanceAnklePosition () const
 Get stance ankle position.
 
Eigen::Vector3d getLeftAnklePosition () const
 Get left ankle position.
 
Eigen::Vector3d getRightAnklePosition () const
 Get right ankle position.
 
double getSagitalPelvisAngle () const
 Get global pelvis upvector angle on sagital plane.
 
double getCoronalPelvisAngle () const
 Get global pelvis upvector angle on coronal plane.
 
double getSagitalLeftLegAngle () const
 Get global left leg angle on sagital plane.
 
double getSagitalRightLegAngle () const
 Get global right leg angle on sagital plane.
 
double getCoronalLeftLegAngle () const
 Get global left leg angle on coronal plane.
 
double getCoronalRightLegAngle () const
 Get global right leg angle on coronal plane.
 

Protected Attributes

std::string mName
 Name.
 
dart::dynamics::SkeletonPtr mSkeleton
 Target skeleton for control.
 
StatemNextState
 Next state. Default is myself.
 
TerminalConditionmTerminalCondition
 Terminal condition.
 
double mBeginTime
 Started time.
 
double mEndTime
 Stopped time.
 
int mFrame
 Frame number.
 
double mElapsedTime
 Elapsed time which is stopped time minus started time.
 
Eigen::VectorXd mDesiredJointPositions
 Desired joint positions.
 
double mDesiredGlobalSwingLegAngleOnSagital
 Desired global angle of swing leg on sagital plane.
 
double mDesiredGlobalSwingLegAngleOnCoronal
 Desired global angle of swing leg on coronal plane.
 
double mDesiredGlobalPelvisAngleOnSagital
 Desired global angle of pelvis on sagital plane.
 
double mDesiredGlobalPelvisAngleOnCoronal
 Desired global angle of pelvis on coronal plane.
 
Eigen::VectorXd mKp
 Proportional gain for PD controller.
 
Eigen::VectorXd mKd
 Derivative gain PD controller.
 
Eigen::VectorXd mSagitalCd
 Feedback gain for com.
 
Eigen::VectorXd mSagitalCv
 Feedback gain for velocity of com.
 
Eigen::VectorXd mCoronalCd
 Feedback gain for com.
 
Eigen::VectorXd mCoronalCv
 Feedback gain for velocity of com.
 
Eigen::VectorXd mTorque
 Computeed control force.
 
std::map< const std::string, int > mJointMap
 Joint map.
 

Detailed Description

class State

Member Function Documentation

◆ begin() [1/2]

void State::begin ( double  _currentTime)
virtual

Initiate state.

This is called when the state machine transite from the previous state to this state.

◆ begin() [2/2]

virtual void State::begin ( double  _currentTime)
virtual

Initiate state.

This is called when the state machine transite from the previous state to this state.

◆ end() [1/2]

virtual void State::end ( double  _currentTime)
virtual

Finalize state.

This is called when the state machine stransite from this state to the next state.

◆ end() [2/2]

void State::end ( double  _currentTime)
virtual

Finalize state.

This is called when the state machine stransite from this state to the next state.


The documentation for this class was generated from the following files: