| 
    Aikido
    
   | 
 
Robot base class for defining basic behaviors common to most robots. More...
#include <aikido/robot/Robot.hpp>
  
Public Member Functions | |
| Robot (dart::dynamics::SkeletonPtr skeleton, const std::string name="robot", bool addDefaultExecutors=true) | |
| Construct a new Robot object.  More... | |
| Robot (dart::dynamics::ReferentialSkeletonPtr refSkeleton, Robot *rootRobot, dart::collision::CollisionDetectorPtr collisionDetector, std::shared_ptr< dart::collision::BodyNodeCollisionFilter > collisionFilter, const std::string name="subrobot") | |
| Construct a new Robot as subrobot.  More... | |
| virtual | ~Robot ()=default | 
| Destructor.  More... | |
| virtual void | ignoreSelfCollisionPairs (const std::vector< std::pair< std::string, std::string >> bodyNodeList) | 
| Manually add pairs of body nodes for which collision is ignored Note: adjacent body pairs are already ignored.  More... | |
| virtual void | enforceSelfCollisionPairs (const std::vector< std::pair< std::string, std::string >> bodyNodeList) | 
| Manually remove pairs of body nodes for which collision constraints are enforced.  More... | |
| virtual void | step (const std::chrono::system_clock::time_point &timepoint) | 
| Steps the robot (and underlying executors and subrobots) through time.  More... | |
| constraint::dart::CollisionFreePtr | getSelfCollisionConstraint () const | 
| Get the self-collision constraint of the robot.  More... | |
| constraint::TestablePtr | combineCollisionConstraint (const constraint::dart::CollisionFreePtr &collisionFree) const | 
| Given a collision constraint, returns it combined with the self-collision constraint of the entire robot.  More... | |
| constraint::TestablePtr | getWorldCollisionConstraint (const std::vector< std::string > bodyNames=std::vector< std::string >()) const | 
| Get the collision constraint between this (sub)robot and selected bodies within its World, combined with its self-collision constraint.  More... | |
| virtual RobotPtr | registerSubRobot (dart::dynamics::ReferentialSkeletonPtr refSkeleton, const std::string &name) | 
| Registers a subset of the joints of the skeleton as a new robot.  More... | |
| RobotPtr | getSubRobotByName (const std::string &name) const | 
| Get existing subrobot pointer.  More... | |
| Eigen::VectorXd | getNamedConfiguration (const std::string &name) const | 
| Returns a named configuration, or size-0 vector if not found.  More... | |
| void | setNamedConfigurations (std::unordered_map< std::string, const Eigen::VectorXd > namedConfigurations) | 
| Sets the list of named configurations.  More... | |
| trajectory::TrajectoryPtr | planToConfiguration (const Eigen::VectorXd &goalConf, const constraint::TestablePtr &testableConstraint, const std::shared_ptr< planner::ConfigurationToConfigurationPlanner > &planner=nullptr, const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > trajPostProcessor=nullptr) const | 
| Plan the robot to a specific configuration.  More... | |
| trajectory::TrajectoryPtr | planToConfiguration (const Eigen::VectorXd &goalConf, const std::shared_ptr< planner::ConfigurationToConfigurationPlanner > &planner=nullptr, const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > trajPostProcessor=nullptr) const | 
| Default to selfCollisionConstraint.  More... | |
| trajectory::TrajectoryPtr | planToOffset (const std::string bodyNodeName, const Eigen::Vector3d &offset, const constraint::TestablePtr &testableConstraint, const std::shared_ptr< planner::dart::ConfigurationToEndEffectorOffsetPlanner > &planner=nullptr, const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > trajPostProcessor=nullptr) const | 
| Plan a specific body node of the robot to a position offset.  More... | |
| trajectory::TrajectoryPtr | planToOffset (const std::string bodyNodeName, const Eigen::Vector3d &offset, const std::shared_ptr< planner::dart::ConfigurationToEndEffectorOffsetPlanner > &planner=nullptr, const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > trajPostProcessor=nullptr) const | 
| Default to selfCollisionConstraint.  More... | |
| trajectory::TrajectoryPtr | planToPoseOffset (const std::string bodyNodeName, const Eigen::Vector3d &offset, const Eigen::Vector3d &rotation, const constraint::TestablePtr &testableConstraint, const std::shared_ptr< planner::dart::ConfigurationToEndEffectorPosePlanner > &planner=nullptr, const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > trajPostProcessor=nullptr) const | 
| Plan a specific body node of the robot to a pose offset (i.e.  More... | |
| trajectory::TrajectoryPtr | planToPoseOffset (const std::string bodyNodeName, const Eigen::Vector3d &offset, const Eigen::Vector3d &rotation, const std::shared_ptr< planner::dart::ConfigurationToEndEffectorPosePlanner > &planner=nullptr, const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > trajPostProcessor=nullptr) const | 
| Default to selfCollisionConstraint.  More... | |
| trajectory::TrajectoryPtr | planToTSR (const std::string bodyNodeName, const constraint::dart::TSRPtr &tsr, const constraint::TestablePtr &testableConstraint, const util::PlanToTSRParameters ¶ms=util::PlanToTSRParameters(), const std::shared_ptr< planner::ConfigurationToConfigurationPlanner > &planner=nullptr, const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > trajPostProcessor=nullptr, const distance::ConstConfigurationRankerPtr &ranker=nullptr) const | 
| Plan a specific body node of the robot to a sample configuraiton within a Task Space Region.  More... | |
| trajectory::TrajectoryPtr | planToTSR (const std::string bodyNodeName, const constraint::dart::TSRPtr &tsr, const util::PlanToTSRParameters ¶ms=util::PlanToTSRParameters(), const std::shared_ptr< planner::ConfigurationToConfigurationPlanner > &planner=nullptr, const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > trajPostProcessor=nullptr, const distance::ConstConfigurationRankerPtr &ranker=nullptr) const | 
| Default to selfCollisionConstraint.  More... | |
| virtual void | clearExecutors () | 
| Deactivates the active executor.  More... | |
| virtual void | deactivateExecutor () | 
| Deactivates the active executor.  More... | |
| virtual aikido::control::ExecutorPtr | getActiveExecutor () | 
| Retrieves the active executor.  More... | |
| virtual int | registerExecutor (aikido::control::ExecutorPtr executor, std::string desiredName="") | 
| Add an executor to the inactive executors list.  More... | |
| virtual bool | activateExecutor (const int id) | 
| Deactivates the current active executor.  More... | |
| virtual bool | activateExecutor (const std::string name) | 
| Convenience: Activates executor using name Deactivates the current active executor.  More... | |
| virtual bool | activateExecutor (const aikido::control::ExecutorType type) | 
| Convenience: Deactivates the current active executor.  More... | |
| template<aikido::control::ExecutorType T> | |
| std::future< int > | executeJointCommand (const std::vector< double > &command, const std::chrono::duration< double > &timeout) | 
| Convenience: executes given joint command on the robot.  More... | |
| std::future< void > | executeTrajectory (const trajectory::TrajectoryPtr &trajectory) | 
| Convenience: executes given trajectory on the robot.  More... | |
| virtual void | cancelAllCommands (bool includeSubrobots=true, bool includeParents=false, const std::vector< std::string > excludeSubrobots=std::vector< std::string >()) | 
| Cancels all running commands on this robot.  More... | |
| std::string | getName () const | 
| dart::dynamics::MetaSkeletonPtr | getMetaSkeletonClone () const | 
| dart::dynamics::MetaSkeletonPtr | getMetaSkeleton () | 
| const dart::dynamics::MetaSkeletonPtr | getMetaSkeleton () const | 
| Eigen::VectorXd | getCurrentConfiguration () const | 
| common::UniqueRNGPtr | cloneRNG () const | 
| void | setRNG (common::UniqueRNGPtr rng) | 
| aikido::planner::WorldPtr | getWorld () const | 
| void | setWorld (aikido::planner::WorldPtr world) | 
| void | setDefaultPostProcessor (const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > trajPostProcessor) | 
| std::shared_ptr< aikido::planner::TrajectoryPostProcessor > | getDefaultPostProcessor () const | 
| void | setEnablePostProcessing (bool enable=true) | 
| dart::dynamics::ConstSkeletonPtr | getRootSkeleton () const | 
| dart::dynamics::SkeletonPtr | getRootSkeleton () | 
| util::VectorFieldPlannerParameters | getVFParams () const | 
| void | setVFParams (util::VectorFieldPlannerParameters params) | 
Protected Types | |
| using | ConfigurationMap = std::unordered_map< std::string, const Eigen::VectorXd > | 
Protected Member Functions | |
| virtual bool | validateSubRobot (dart::dynamics::ReferentialSkeletonPtr refSkeleton, const std::string &name) | 
| Checks validity of subrobot for registration: name should be unique.  More... | |
Protected Attributes | |
| std::string | mName | 
| dart::dynamics::MetaSkeletonPtr | mMetaSkeleton | 
| aikido::statespace::dart::MetaSkeletonStateSpacePtr | mStateSpace | 
| int | mActiveExecutor {-1} | 
| std::vector< aikido::control::ExecutorPtr > | mExecutors | 
| std::unordered_map< std::string, int > | mExecutorsNameMap | 
| Robot * | mParentRobot {nullptr} | 
| std::set< std::string > | mDofs | 
| std::unordered_map< std::string, RobotPtr > | mSubRobots | 
| dart::collision::CollisionDetectorPtr | mCollisionDetector | 
| std::shared_ptr< dart::collision::BodyNodeCollisionFilter > | mSelfCollisionFilter | 
| bool | mEnablePostProcessing {false} | 
| std::shared_ptr< aikido::planner::TrajectoryPostProcessor > | mDefaultPostProcessor {nullptr} | 
| std::unique_ptr< common::RNG > | mRng | 
| aikido::planner::WorldPtr | mWorld {nullptr} | 
| ConfigurationMap | mNamedConfigurations | 
| util::VectorFieldPlannerParameters | mVFParams | 
Robot base class for defining basic behaviors common to most robots.
      
  | 
  protected | 
| aikido::robot::Robot::Robot | ( | dart::dynamics::SkeletonPtr | skeleton, | 
| const std::string | name = "robot",  | 
        ||
| bool | addDefaultExecutors = true  | 
        ||
| ) | 
Construct a new Robot object.
| [in] | skeleton | The skeleton defining the robot. | 
| [in] | name | The name of the robot. | 
| [in] | addDefaultExecutors | if true, adds the following: KinematicSimulationTrajectoryExecutor (active) KinematicSimulationPositionExecutor (inactive) KinematicSimulationVelocityExecutor (inactive) | 
| aikido::robot::Robot::Robot | ( | dart::dynamics::ReferentialSkeletonPtr | refSkeleton, | 
| Robot * | rootRobot, | ||
| dart::collision::CollisionDetectorPtr | collisionDetector, | ||
| std::shared_ptr< dart::collision::BodyNodeCollisionFilter > | collisionFilter, | ||
| const std::string | name = "subrobot"  | 
        ||
| ) | 
Construct a new Robot as subrobot.
| [in] | refSkeleton | The metaskeleton defining the robot. | 
| [in] | rootRobot | Pointer to parent robot | 
| [in] | collisionDetector | Parent robot's collision detector | 
| [in] | collisionFilter | Parent robot's collision filter | 
| [in] | name | Unique Name of sub-robot | 
      
  | 
  virtualdefault | 
Destructor.
      
  | 
  virtual | 
Convenience: Deactivates the current active executor.
Activates the most recently registered executor of the given type.
| [in] | type | of executor to activate. | 
      
  | 
  virtual | 
Deactivates the current active executor.
Sets an executor from the inactive executor list to be the active executor. Holds and releases DoFs as needed.
| [in] | id | of executor on executor list | 
Reimplemented in aikido::robot::ros::RosRobot.
      
  | 
  virtual | 
Convenience: Activates executor using name Deactivates the current active executor.
Sets an executor from the inactive executor list to be the active executor. Holds and releases DoFs as needed.
| [in] | id | of executor on executor list | 
      
  | 
  virtual | 
Cancels all running commands on this robot.
| [in] | includeSubrobots | Also cancel commands on all subrobots. | 
| [in] | includeParents | Also cancel commands on parent robots | 
| [in] | excludedSubrobots | Ignores theese subrobots when issuing cancellations | 
      
  | 
  virtual | 
Deactivates the active executor.
Clears the inactive executor list. Forgets all unique id.
| common::UniqueRNGPtr aikido::robot::Robot::cloneRNG | ( | ) | const | 
| constraint::TestablePtr aikido::robot::Robot::combineCollisionConstraint | ( | const constraint::dart::CollisionFreePtr & | collisionFree | ) | const | 
Given a collision constraint, returns it combined with the self-collision constraint of the entire robot.
| [in] | collisionFree | The collision constraint that is to be tied with root robot's self-collision constraint. | 
      
  | 
  virtual | 
Deactivates the active executor.
Reimplemented in aikido::robot::ros::RosRobot.
      
  | 
  virtual | 
Manually remove pairs of body nodes for which collision constraints are enforced.
Note: adjacent body pairs start ignored.
| [in] | bodyNodeList | list of pairs of body node names | 
| std::future< int > aikido::robot::Robot::executeJointCommand | ( | const std::vector< double > & | command, | 
| const std::chrono::duration< double > & | timeout | ||
| ) | 
Convenience: executes given joint command on the robot.
future will have exception if active executor is not of the appropriate type.
| [in] | type | Type of JointCommandExecutor to look for. | 
| [in] | command | The joint command to execute. | 
| [in] | timeout | Timeout for the joint command | 
| std::future<void> aikido::robot::Robot::executeTrajectory | ( | const trajectory::TrajectoryPtr & | trajectory | ) | 
Convenience: executes given trajectory on the robot.
future will have exception if active executor is not of type TrajectoryExecutor
| [in] | trajectory | The trajectory to execute. | 
      
  | 
  virtual | 
Retrieves the active executor.
| Eigen::VectorXd aikido::robot::Robot::getCurrentConfiguration | ( | ) | const | 
| std::shared_ptr<aikido::planner::TrajectoryPostProcessor> aikido::robot::Robot::getDefaultPostProcessor | ( | ) | const | 
| dart::dynamics::MetaSkeletonPtr aikido::robot::Robot::getMetaSkeleton | ( | ) | 
| const dart::dynamics::MetaSkeletonPtr aikido::robot::Robot::getMetaSkeleton | ( | ) | const | 
| dart::dynamics::MetaSkeletonPtr aikido::robot::Robot::getMetaSkeletonClone | ( | ) | const | 
| std::string aikido::robot::Robot::getName | ( | ) | const | 
| Eigen::VectorXd aikido::robot::Robot::getNamedConfiguration | ( | const std::string & | name | ) | const | 
Returns a named configuration, or size-0 vector if not found.
| [in] | name | Name of the configuration. | 
| dart::dynamics::SkeletonPtr aikido::robot::Robot::getRootSkeleton | ( | ) | 
| dart::dynamics::ConstSkeletonPtr aikido::robot::Robot::getRootSkeleton | ( | ) | const | 
| constraint::dart::CollisionFreePtr aikido::robot::Robot::getSelfCollisionConstraint | ( | ) | const | 
Get the self-collision constraint of the robot.
| RobotPtr aikido::robot::Robot::getSubRobotByName | ( | const std::string & | name | ) | const | 
Get existing subrobot pointer.
Or nullptr if not found.
| [in] | name | Name of the subrobot. | 
| util::VectorFieldPlannerParameters aikido::robot::Robot::getVFParams | ( | ) | const | 
| aikido::planner::WorldPtr aikido::robot::Robot::getWorld | ( | ) | const | 
| constraint::TestablePtr aikido::robot::Robot::getWorldCollisionConstraint | ( | const std::vector< std::string > | bodyNames = std::vector< std::string >() | ) | const | 
Get the collision constraint between this (sub)robot and selected bodies within its World, combined with its self-collision constraint.
| [in] | bodyNames | Names of the bodies in the robot's world to check collision with. Leave blank to check with all non-robot bodies. | 
      
  | 
  virtual | 
Manually add pairs of body nodes for which collision is ignored Note: adjacent body pairs are already ignored.
| [in] | bodyNodeList | list of pairs of body node names | 
| trajectory::TrajectoryPtr aikido::robot::Robot::planToConfiguration | ( | const Eigen::VectorXd & | goalConf, | 
| const constraint::TestablePtr & | testableConstraint, | ||
| const std::shared_ptr< planner::ConfigurationToConfigurationPlanner > & | planner = nullptr,  | 
        ||
| const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > | trajPostProcessor = nullptr  | 
        ||
| ) | const | 
Plan the robot to a specific configuration.
| [in] | goalConf | Goal configuration Returns nullptr if not in robot's statespace. | 
| [in] | testableConstraint | Planning (e.g. collision) constraints, set to nullptr for no constraints (not recommended) | 
| [in] | planner | Configuration planner, defaults to Snap Planner | 
| trajectory::TrajectoryPtr aikido::robot::Robot::planToConfiguration | ( | const Eigen::VectorXd & | goalConf, | 
| const std::shared_ptr< planner::ConfigurationToConfigurationPlanner > & | planner = nullptr,  | 
        ||
| const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > | trajPostProcessor = nullptr  | 
        ||
| ) | const | 
Default to selfCollisionConstraint.
| trajectory::TrajectoryPtr aikido::robot::Robot::planToOffset | ( | const std::string | bodyNodeName, | 
| const Eigen::Vector3d & | offset, | ||
| const constraint::TestablePtr & | testableConstraint, | ||
| const std::shared_ptr< planner::dart::ConfigurationToEndEffectorOffsetPlanner > & | planner = nullptr,  | 
        ||
| const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > | trajPostProcessor = nullptr  | 
        ||
| ) | const | 
Plan a specific body node of the robot to a position offset.
| [in] | bodyNodeName | Bodynode (usually the end effector) to offset | 
| [in] | offset | Position offset in R^3 | 
| [in] | testableConstraint | Planning (e.g. collision) constraints, set to nullptr for no constraints (not recommended) | 
| [in] | planner | Configuration-to-Offset planner, defaults to VectorFieldConfigurationToEndEffectorOffsetPlanner with robot::util::defaultVFParams | 
| trajectory::TrajectoryPtr aikido::robot::Robot::planToOffset | ( | const std::string | bodyNodeName, | 
| const Eigen::Vector3d & | offset, | ||
| const std::shared_ptr< planner::dart::ConfigurationToEndEffectorOffsetPlanner > & | planner = nullptr,  | 
        ||
| const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > | trajPostProcessor = nullptr  | 
        ||
| ) | const | 
Default to selfCollisionConstraint.
| trajectory::TrajectoryPtr aikido::robot::Robot::planToPoseOffset | ( | const std::string | bodyNodeName, | 
| const Eigen::Vector3d & | offset, | ||
| const Eigen::Vector3d & | rotation, | ||
| const constraint::TestablePtr & | testableConstraint, | ||
| const std::shared_ptr< planner::dart::ConfigurationToEndEffectorPosePlanner > & | planner = nullptr,  | 
        ||
| const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > | trajPostProcessor = nullptr  | 
        ||
| ) | const | 
Plan a specific body node of the robot to a pose offset (i.e.
position offset + rotation).
| [in] | bodyNodeName | Bodynode (usually the end effector) to offset | 
| [in] | offset | Translation in R^3 (world Frame) | 
| [in] | rotation | Axis in R^3, norm is angle (world Frame) | 
| [in] | testableConstraint | Planning (e.g. collision) constraints, set to nullptr for no constraints (not recommended) | 
| [in] | planner | Configuration planner, defaults to VectorFieldConfigurationToEndEffectorOffsetPlanner with robot::util::defaultVFParams | 
| trajectory::TrajectoryPtr aikido::robot::Robot::planToPoseOffset | ( | const std::string | bodyNodeName, | 
| const Eigen::Vector3d & | offset, | ||
| const Eigen::Vector3d & | rotation, | ||
| const std::shared_ptr< planner::dart::ConfigurationToEndEffectorPosePlanner > & | planner = nullptr,  | 
        ||
| const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > | trajPostProcessor = nullptr  | 
        ||
| ) | const | 
Default to selfCollisionConstraint.
| trajectory::TrajectoryPtr aikido::robot::Robot::planToTSR | ( | const std::string | bodyNodeName, | 
| const constraint::dart::TSRPtr & | tsr, | ||
| const constraint::TestablePtr & | testableConstraint, | ||
| const util::PlanToTSRParameters & | params = util::PlanToTSRParameters(),  | 
        ||
| const std::shared_ptr< planner::ConfigurationToConfigurationPlanner > & | planner = nullptr,  | 
        ||
| const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > | trajPostProcessor = nullptr,  | 
        ||
| const distance::ConstConfigurationRankerPtr & | ranker = nullptr  | 
        ||
| ) | const | 
Plan a specific body node of the robot to a sample configuraiton within a Task Space Region.
| [in] | bodyNodeName | Bodynode (usually the end effector) whose frame should end up in the TSR. | 
| [in] | tsr | 
| [in] | testableConstraint | Planning (e.g. collision) constraints, set to nullptr for no constraints (not recommended) | 
| [in] | maxSamplingTries | Maximum number of times for the sample generator to retry sampling from the TSR. | 
| [in] | batchSize | Number of TSR samples to include per ranked batch. | 
| [in] | maxBatches | Maximum number of ranked batches to run when planning to TSR samples. | 
| [in] | planner | Base configuration planner, defaults to Snap Planner | 
| [in] | ranker | Ranker to rank the sampled configurations. If nullptr, NominalConfigurationRanker is used with the current metaSkeleton pose. | 
| trajectory::TrajectoryPtr aikido::robot::Robot::planToTSR | ( | const std::string | bodyNodeName, | 
| const constraint::dart::TSRPtr & | tsr, | ||
| const util::PlanToTSRParameters & | params = util::PlanToTSRParameters(),  | 
        ||
| const std::shared_ptr< planner::ConfigurationToConfigurationPlanner > & | planner = nullptr,  | 
        ||
| const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > | trajPostProcessor = nullptr,  | 
        ||
| const distance::ConstConfigurationRankerPtr & | ranker = nullptr  | 
        ||
| ) | const | 
Default to selfCollisionConstraint.
      
  | 
  virtual | 
Add an executor to the inactive executors list.
Releases DoFs held by executor if held.
| [in] | executor | The Executor to add to the inactive list. | 
| [in] | desiredName | The desired name for the executor. | 
      
  | 
  virtual | 
Registers a subset of the joints of the skeleton as a new robot.
Must be disjoint from other subrobots.
| [in] | metaSkeleton | The referential skeleton corresponding to the subrobot. | 
| [in] | name | Name of the subrobot. | 
| void aikido::robot::Robot::setDefaultPostProcessor | ( | const std::shared_ptr< aikido::planner::TrajectoryPostProcessor > | trajPostProcessor | ) | 
| void aikido::robot::Robot::setEnablePostProcessing | ( | bool | enable = true | ) | 
| void aikido::robot::Robot::setNamedConfigurations | ( | std::unordered_map< std::string, const Eigen::VectorXd > | namedConfigurations | ) | 
Sets the list of named configurations.
| [in] | namedConfigurations | Map of name, configuration. | 
| void aikido::robot::Robot::setRNG | ( | common::UniqueRNGPtr | rng | ) | 
| void aikido::robot::Robot::setVFParams | ( | util::VectorFieldPlannerParameters | params | ) | 
| void aikido::robot::Robot::setWorld | ( | aikido::planner::WorldPtr | world | ) | 
      
  | 
  virtual | 
Steps the robot (and underlying executors and subrobots) through time.
Call regularly to update the state of the robot.
| [in] | timepoint | The point in time to step to. | 
Reimplemented in aikido::robot::ros::RosRobot.
      
  | 
  protectedvirtual | 
Checks validity of subrobot for registration: name should be unique.
All body nodes in skeleton should be owned by this robot. Subrobot DoFs should be disjoint.
| [in] | metaSkeleton | The referential skeleton corresponding to the subrobot. | 
| [in] | name | Name of the subrobot. | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected | 
      
  | 
  protected |