Aikido
aikido::robot::Robot Class Reference

Robot base class for defining basic behaviors common to most robots. More...

#include <aikido/robot/Robot.hpp>

Inheritance diagram for aikido::robot::Robot:
aikido::robot::ros::RosRobot

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 &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. More...
 
trajectory::TrajectoryPtr 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. 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::TrajectoryPostProcessorgetDefaultPostProcessor () 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::ExecutorPtrmExecutors
 
std::unordered_map< std::string, int > mExecutorsNameMap
 
RobotmParentRobot {nullptr}
 
std::set< std::string > mDofs
 
std::unordered_map< std::string, RobotPtrmSubRobots
 
dart::collision::CollisionDetectorPtr mCollisionDetector
 
std::shared_ptr< dart::collision::BodyNodeCollisionFilter > mSelfCollisionFilter
 
bool mEnablePostProcessing {false}
 
std::shared_ptr< aikido::planner::TrajectoryPostProcessormDefaultPostProcessor {nullptr}
 
std::unique_ptr< common::RNGmRng
 
aikido::planner::WorldPtr mWorld {nullptr}
 
ConfigurationMap mNamedConfigurations
 
util::VectorFieldPlannerParameters mVFParams
 

Detailed Description

Robot base class for defining basic behaviors common to most robots.

Member Typedef Documentation

◆ ConfigurationMap

using aikido::robot::Robot::ConfigurationMap = std::unordered_map<std::string, const Eigen::VectorXd>
protected

Constructor & Destructor Documentation

◆ Robot() [1/2]

aikido::robot::Robot::Robot ( dart::dynamics::SkeletonPtr  skeleton,
const std::string  name = "robot",
bool  addDefaultExecutors = true 
)

Construct a new Robot object.

Parameters
[in]skeletonThe skeleton defining the robot.
[in]nameThe name of the robot.
[in]addDefaultExecutorsif true, adds the following: KinematicSimulationTrajectoryExecutor (active) KinematicSimulationPositionExecutor (inactive) KinematicSimulationVelocityExecutor (inactive)

◆ Robot() [2/2]

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.

Parameters
[in]refSkeletonThe metaskeleton defining the robot.
[in]rootRobotPointer to parent robot
[in]collisionDetectorParent robot's collision detector
[in]collisionFilterParent robot's collision filter
[in]nameUnique Name of sub-robot

◆ ~Robot()

virtual aikido::robot::Robot::~Robot ( )
virtualdefault

Destructor.

Member Function Documentation

◆ activateExecutor() [1/3]

virtual bool aikido::robot::Robot::activateExecutor ( const aikido::control::ExecutorType  type)
virtual

Convenience: Deactivates the current active executor.

Activates the most recently registered executor of the given type.

Parameters
[in]typeof executor to activate.
Returns
True if successful. If false, all executors are inactive.

◆ activateExecutor() [2/3]

virtual bool aikido::robot::Robot::activateExecutor ( const int  id)
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.

Parameters
[in]idof executor on executor list
Returns
True if successful. If false, all executors are inactive.

Reimplemented in aikido::robot::ros::RosRobot.

◆ activateExecutor() [3/3]

virtual bool aikido::robot::Robot::activateExecutor ( const std::string  name)
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.

Parameters
[in]idof executor on executor list
Returns
True if successful. If false, all executors are inactive.

◆ cancelAllCommands()

virtual void aikido::robot::Robot::cancelAllCommands ( bool  includeSubrobots = true,
bool  includeParents = false,
const std::vector< std::string >  excludeSubrobots = std::vector< std::string >() 
)
virtual

Cancels all running commands on this robot.

Parameters
[in]includeSubrobotsAlso cancel commands on all subrobots.
[in]includeParentsAlso cancel commands on parent robots
[in]excludedSubrobotsIgnores theese subrobots when issuing cancellations

◆ clearExecutors()

virtual void aikido::robot::Robot::clearExecutors ( )
virtual

Deactivates the active executor.

Clears the inactive executor list. Forgets all unique id.

◆ cloneRNG()

common::UniqueRNGPtr aikido::robot::Robot::cloneRNG ( ) const

◆ combineCollisionConstraint()

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.

Parameters
[in]collisionFreeThe collision constraint that is to be tied with root robot's self-collision constraint.

◆ deactivateExecutor()

virtual void aikido::robot::Robot::deactivateExecutor ( )
virtual

Deactivates the active executor.

Reimplemented in aikido::robot::ros::RosRobot.

◆ enforceSelfCollisionPairs()

virtual void aikido::robot::Robot::enforceSelfCollisionPairs ( const std::vector< std::pair< std::string, std::string >>  bodyNodeList)
virtual

Manually remove pairs of body nodes for which collision constraints are enforced.

Note: adjacent body pairs start ignored.

Parameters
[in]bodyNodeListlist of pairs of body node names

◆ executeJointCommand()

template<aikido::control::ExecutorType T>
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.

Parameters
[in]typeType of JointCommandExecutor to look for.
[in]commandThe joint command to execute.
[in]timeoutTimeout for the joint command

◆ executeTrajectory()

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

Parameters
[in]trajectoryThe trajectory to execute.

◆ getActiveExecutor()

virtual aikido::control::ExecutorPtr aikido::robot::Robot::getActiveExecutor ( )
virtual

Retrieves the active executor.

◆ getCurrentConfiguration()

Eigen::VectorXd aikido::robot::Robot::getCurrentConfiguration ( ) const

◆ getDefaultPostProcessor()

std::shared_ptr<aikido::planner::TrajectoryPostProcessor> aikido::robot::Robot::getDefaultPostProcessor ( ) const

◆ getMetaSkeleton() [1/2]

dart::dynamics::MetaSkeletonPtr aikido::robot::Robot::getMetaSkeleton ( )

◆ getMetaSkeleton() [2/2]

const dart::dynamics::MetaSkeletonPtr aikido::robot::Robot::getMetaSkeleton ( ) const

◆ getMetaSkeletonClone()

dart::dynamics::MetaSkeletonPtr aikido::robot::Robot::getMetaSkeletonClone ( ) const

◆ getName()

std::string aikido::robot::Robot::getName ( ) const

◆ getNamedConfiguration()

Eigen::VectorXd aikido::robot::Robot::getNamedConfiguration ( const std::string &  name) const

Returns a named configuration, or size-0 vector if not found.

Parameters
[in]nameName of the configuration.

◆ getRootSkeleton() [1/2]

dart::dynamics::SkeletonPtr aikido::robot::Robot::getRootSkeleton ( )

◆ getRootSkeleton() [2/2]

dart::dynamics::ConstSkeletonPtr aikido::robot::Robot::getRootSkeleton ( ) const

◆ getSelfCollisionConstraint()

constraint::dart::CollisionFreePtr aikido::robot::Robot::getSelfCollisionConstraint ( ) const

Get the self-collision constraint of the robot.

◆ getSubRobotByName()

RobotPtr aikido::robot::Robot::getSubRobotByName ( const std::string &  name) const

Get existing subrobot pointer.

Or nullptr if not found.

Parameters
[in]nameName of the subrobot.

◆ getVFParams()

util::VectorFieldPlannerParameters aikido::robot::Robot::getVFParams ( ) const

◆ getWorld()

aikido::planner::WorldPtr aikido::robot::Robot::getWorld ( ) const

◆ getWorldCollisionConstraint()

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.

Parameters
[in]bodyNamesNames of the bodies in the robot's world to check collision with. Leave blank to check with all non-robot bodies.

◆ ignoreSelfCollisionPairs()

virtual void aikido::robot::Robot::ignoreSelfCollisionPairs ( const std::vector< std::pair< std::string, std::string >>  bodyNodeList)
virtual

Manually add pairs of body nodes for which collision is ignored Note: adjacent body pairs are already ignored.

Parameters
[in]bodyNodeListlist of pairs of body node names

◆ planToConfiguration() [1/2]

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.

Parameters
[in]goalConfGoal configuration Returns nullptr if not in robot's statespace.
[in]testableConstraintPlanning (e.g. collision) constraints, set to nullptr for no constraints (not recommended)
[in]plannerConfiguration planner, defaults to Snap Planner

◆ planToConfiguration() [2/2]

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.

◆ planToOffset() [1/2]

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.

Parameters
[in]bodyNodeNameBodynode (usually the end effector) to offset
[in]offsetPosition offset in R^3
[in]testableConstraintPlanning (e.g. collision) constraints, set to nullptr for no constraints (not recommended)
[in]plannerConfiguration-to-Offset planner, defaults to VectorFieldConfigurationToEndEffectorOffsetPlanner with robot::util::defaultVFParams

◆ planToOffset() [2/2]

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.

◆ planToPoseOffset() [1/2]

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).

Parameters
[in]bodyNodeNameBodynode (usually the end effector) to offset
[in]offsetTranslation in R^3 (world Frame)
[in]rotationAxis in R^3, norm is angle (world Frame)
[in]testableConstraintPlanning (e.g. collision) constraints, set to nullptr for no constraints (not recommended)
[in]plannerConfiguration planner, defaults to VectorFieldConfigurationToEndEffectorOffsetPlanner with robot::util::defaultVFParams

◆ planToPoseOffset() [2/2]

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.

◆ planToTSR() [1/2]

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.

Parameters
[in]bodyNodeNameBodynode (usually the end effector) whose frame should end up in the TSR.
[in]tsr
See also
constraint::dart::TSR
Parameters
[in]testableConstraintPlanning (e.g. collision) constraints, set to nullptr for no constraints (not recommended)
[in]maxSamplingTriesMaximum number of times for the sample generator to retry sampling from the TSR.
[in]batchSizeNumber of TSR samples to include per ranked batch.
[in]maxBatchesMaximum number of ranked batches to run when planning to TSR samples.
[in]plannerBase configuration planner, defaults to Snap Planner
[in]rankerRanker to rank the sampled configurations. If nullptr, NominalConfigurationRanker is used with the current metaSkeleton pose.
Returns
Trajectory to a sample in TSR, or nullptr if planning fails.

◆ planToTSR() [2/2]

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.

◆ registerExecutor()

virtual int aikido::robot::Robot::registerExecutor ( aikido::control::ExecutorPtr  executor,
std::string  desiredName = "" 
)
virtual

Add an executor to the inactive executors list.

Releases DoFs held by executor if held.

Parameters
[in]executorThe Executor to add to the inactive list.
[in]desiredNameThe desired name for the executor.
Returns
A robot-unique non-negative ID (negative implies failure).

◆ registerSubRobot()

virtual RobotPtr aikido::robot::Robot::registerSubRobot ( dart::dynamics::ReferentialSkeletonPtr  refSkeleton,
const std::string &  name 
)
virtual

Registers a subset of the joints of the skeleton as a new robot.

Must be disjoint from other subrobots.

Parameters
[in]metaSkeletonThe referential skeleton corresponding to the subrobot.
[in]nameName of the subrobot.

◆ setDefaultPostProcessor()

void aikido::robot::Robot::setDefaultPostProcessor ( const std::shared_ptr< aikido::planner::TrajectoryPostProcessor trajPostProcessor)

◆ setEnablePostProcessing()

void aikido::robot::Robot::setEnablePostProcessing ( bool  enable = true)

◆ setNamedConfigurations()

void aikido::robot::Robot::setNamedConfigurations ( std::unordered_map< std::string, const Eigen::VectorXd >  namedConfigurations)

Sets the list of named configurations.

Parameters
[in]namedConfigurationsMap of name, configuration.

◆ setRNG()

void aikido::robot::Robot::setRNG ( common::UniqueRNGPtr  rng)

◆ setVFParams()

void aikido::robot::Robot::setVFParams ( util::VectorFieldPlannerParameters  params)

◆ setWorld()

void aikido::robot::Robot::setWorld ( aikido::planner::WorldPtr  world)

◆ step()

virtual void aikido::robot::Robot::step ( const std::chrono::system_clock::time_point &  timepoint)
virtual

Steps the robot (and underlying executors and subrobots) through time.

Call regularly to update the state of the robot.

Parameters
[in]timepointThe point in time to step to.

Reimplemented in aikido::robot::ros::RosRobot.

◆ validateSubRobot()

virtual bool aikido::robot::Robot::validateSubRobot ( dart::dynamics::ReferentialSkeletonPtr  refSkeleton,
const std::string &  name 
)
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.

Parameters
[in]metaSkeletonThe referential skeleton corresponding to the subrobot.
[in]nameName of the subrobot.

Member Data Documentation

◆ mActiveExecutor

int aikido::robot::Robot::mActiveExecutor {-1}
protected

◆ mCollisionDetector

dart::collision::CollisionDetectorPtr aikido::robot::Robot::mCollisionDetector
protected

◆ mDefaultPostProcessor

std::shared_ptr<aikido::planner::TrajectoryPostProcessor> aikido::robot::Robot::mDefaultPostProcessor {nullptr}
protected

◆ mDofs

std::set<std::string> aikido::robot::Robot::mDofs
protected

◆ mEnablePostProcessing

bool aikido::robot::Robot::mEnablePostProcessing {false}
protected

◆ mExecutors

std::vector<aikido::control::ExecutorPtr> aikido::robot::Robot::mExecutors
protected

◆ mExecutorsNameMap

std::unordered_map<std::string, int> aikido::robot::Robot::mExecutorsNameMap
protected

◆ mMetaSkeleton

dart::dynamics::MetaSkeletonPtr aikido::robot::Robot::mMetaSkeleton
protected

◆ mName

std::string aikido::robot::Robot::mName
protected

◆ mNamedConfigurations

ConfigurationMap aikido::robot::Robot::mNamedConfigurations
protected

◆ mParentRobot

Robot* aikido::robot::Robot::mParentRobot {nullptr}
protected

◆ mRng

std::unique_ptr<common::RNG> aikido::robot::Robot::mRng
protected

◆ mSelfCollisionFilter

std::shared_ptr<dart::collision::BodyNodeCollisionFilter> aikido::robot::Robot::mSelfCollisionFilter
protected

◆ mStateSpace

aikido::statespace::dart::MetaSkeletonStateSpacePtr aikido::robot::Robot::mStateSpace
protected

◆ mSubRobots

std::unordered_map<std::string, RobotPtr> aikido::robot::Robot::mSubRobots
protected

◆ mVFParams

util::VectorFieldPlannerParameters aikido::robot::Robot::mVFParams
protected

◆ mWorld

aikido::planner::WorldPtr aikido::robot::Robot::mWorld {nullptr}
protected