33 #ifndef EXAMPLES_ATLASSIMBICON_CONTROLLER_HPP_ 34 #define EXAMPLES_ATLASSIMBICON_CONTROLLER_HPP_ 38 #include <Eigen/Dense> 40 #include <dart/dart.hpp> 53 dart::dynamics::SkeletonPtr _atlasRobot,
64 dart::dynamics::SkeletonPtr getAtlasRobot();
83 void keyboard(
unsigned char _key,
int _x,
int _y,
double _currentTime);
154 bool _containStateMachine(
const StateMachine* _stateMachine)
const;
158 bool _containStateMachine(
const std::string& _name)
const;
161 StateMachine* _findStateMachine(
const std::string& _name)
const;
164 void _buildStateMachines();
179 void _setJointDamping();
188 dart::dynamics::WeldJointConstraintPtr mWeldJointConstraintPelvis;
191 dart::dynamics::WeldJointConstraintPtr mWeldJointConstraintLeftFoot;
194 dart::dynamics::WeldJointConstraintPtr mWeldJointConstraintRightFoot;
203 #endif // EXAMPLES_ATLASSIMBICON_CONTROLLER_HPP_ std::size_t mCoronalLeftHip
Index for coronal left hip.
Definition: Controller.hpp:135
virtual void update()
Called before every simulation time step in MyWindow class.
Definition: Controller.cpp:91
Implementation of Simbicon (Simple biped locomotion control) for Atlas robot.
Definition: Controller.hpp:48
dart::dynamics::ConstraintSolver * mConstratinSolver
Conllision detector.
Definition: Controller.hpp:117
void keyboard(unsigned char _key, int _x, int _y, double _currentTime)
Keyboard control.
Definition: Controller.cpp:176
StateMachine * getCurrentState()
Get current state machine.
Definition: Controller.cpp:107
virtual ~Controller()
Destructor.
Definition: Controller.cpp:80
StateMachine for Atlas robot.
Definition: StateMachine.hpp:46
bool mPelvisHarnessOn
Flag for pelvis harnessing.
Definition: Controller.hpp:126
void unharnessLeftFoot()
Harness the robot.
Definition: Controller.cpp:291
Controller(dart::dynamics::SkeletonPtr _atlasRobot, dart::dynamics::ConstraintSolver *_collisionSolver)
Constructor.
bool isAllowingControl() const
Get true iff this controller is currently allowing to control the Atlas robot.
Definition: Controller.cpp:162
ConstraintSolver manages constraints and computes constraint impulses.
Definition: ConstraintSolver.hpp:56
void setVerbosity(bool verbosity)
Set the verbosity.
Definition: Controller.cpp:340
dart::dynamics::SkeletonPtr mAtlasRobot
Atlas robot skeleton.
Definition: Controller.hpp:114
double mMaxPelvisHeight
Upper bound for emergency stop.
Definition: Controller.hpp:150
void harnessPelvis()
Harness the robot.
Definition: Controller.cpp:249
void unharnessPelvis()
Unharness the robot.
Definition: Controller.cpp:264
void harnessRightFoot()
Harness the robot.
Definition: Controller.cpp:304
void harnessLeftFoot()
Harness the robot.
Definition: Controller.cpp:277
void unharnessRightFoot()
Harness the robot.
Definition: Controller.cpp:318
std::size_t mCoronalRightHip
Index for coronal right hip.
Definition: Controller.hpp:138
std::size_t mSagitalRightHip
Index for sagital right hip.
Definition: Controller.hpp:144
StateMachine * mCurrentStateMachine
Current state machine.
Definition: Controller.hpp:123
BodyNode class represents a single node of the skeleton.
Definition: BodyNode.hpp:74
std::vector< StateMachine * > mStateMachines
List of state machines.
Definition: Controller.hpp:120
std::size_t mSagitalLeftHip
Index for sagital left hip.
Definition: Controller.hpp:141
double mMinPelvisHeight
Lower bound for emergency stop.
Definition: Controller.hpp:147
void printDebugInfo() const
Print debug information.
Definition: Controller.cpp:224
void changeStateMachine(StateMachine *_stateMachine, double _currentTime)
Change state to _stateMachine.
Definition: Controller.cpp:113
bool mLeftFootHarnessOn
Flag for left foot harnessing.
Definition: Controller.hpp:129
The Configuration struct represents the joint configuration of a Skeleton.
Definition: Skeleton.hpp:94
void resetRobot()
Reset the robot.
Definition: Controller.cpp:331
bool mRightFootHarnessOn
Flag for right foot harnessing.
Definition: Controller.hpp:132