Aikido
aikido::robot::ConcreteManipulator Class Reference

A concrete implementation of a manipulator. More...

#include <aikido/robot/ConcreteManipulator.hpp>

Inheritance diagram for aikido::robot::ConcreteManipulator:
aikido::robot::Manipulator aikido::robot::Robot

Public Member Functions

 ConcreteManipulator (RobotPtr robot, HandPtr hand)
 Constructor. More...
 
virtual ~ConcreteManipulator ()=default
 
virtual ConstHandPtr getHand () const override
 Returns the [const] hand. More...
 
virtual std::unique_ptr< aikido::trajectory::SplinesmoothPath (const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const aikido::trajectory::Trajectory *path, const constraint::TestablePtr &constraint) override
 Returns a timed trajectory that can be executed by the robot. More...
 
virtual std::unique_ptr< aikido::trajectory::SplineretimePath (const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const aikido::trajectory::Trajectory *path) override
 Returns a timed trajectory that can be executed by the robot. More...
 
virtual std::unique_ptr< aikido::trajectory::SplineretimePathWithKunz (const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const aikido::trajectory::Trajectory *path, double maxDeviation, double timestep) override
 Returns a timed trajectory computed with KunzRetimer. More...
 
virtual std::future< void > executeTrajectory (const trajectory::TrajectoryPtr &trajectory) const override
 Executes a trajectory. More...
 
virtual boost::optional< Eigen::VectorXd > getNamedConfiguration (const std::string &name) const override
 Returns a named configuration. More...
 
virtual void setNamedConfigurations (std::unordered_map< std::string, const Eigen::VectorXd > namedConfigurations) override
 Sets the list of named configurations. More...
 
virtual std::string getName () const override
 
virtual dart::dynamics::ConstMetaSkeletonPtr getMetaSkeleton () const override
 
virtual aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr getStateSpace () const override
 
virtual void setRoot (Robot *robot) override
 Sets the root of this robot. More...
 
virtual void step (const std::chrono::system_clock::time_point &timepoint) override
 Simulates up to the provided timepoint. More...
 
virtual constraint::dart::CollisionFreePtr getSelfCollisionConstraint (const statespace::dart::ConstMetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton) const override
 Returns self-collision constraint. More...
 
virtual aikido::constraint::TestablePtr getFullCollisionConstraint (const statespace::dart::ConstMetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const constraint::dart::CollisionFreePtr &collisionFree) const override
 TODO: Consider changing this to return a CollisionFreePtr. More...
 
trajectory::TrajectoryPtr planToEndEffectorOffset (const statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const dart::dynamics::BodyNodePtr &body, const constraint::dart::CollisionFreePtr &collisionFree, const Eigen::Vector3d &direction, double distance, double timelimit, double positionTolerance, double angularTolerance)
 TODO: Replace this with Problem interface. More...
 
trajectory::TrajectoryPtr planEndEffectorStraight (statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const dart::dynamics::BodyNodePtr &body, const constraint::dart::CollisionFreePtr &collisionFree, double distance, double timelimit, double positionTolerance, double angularTolerance)
 TODO: Replace this with Problem interface. More...
 
void setVectorFieldPlannerParameters (const util::VectorFieldPlannerParameters &vfParameters)
 TODO: This should be revisited once we have Planner API. More...
 
void setCRRTPlannerParameters (const util::CRRTPlannerParameters &crrtParameters)
 TODO: This should be revisited once we have Planner API. More...
 
virtual ConstHandPtr getHand () const=0
 Returns the [const] hand. More...
 
HandPtr getHand ()
 Returns the hand. More...
 
virtual dart::dynamics::ConstMetaSkeletonPtr getMetaSkeleton () const=0
 
dart::dynamics::MetaSkeletonPtr getMetaSkeleton ()
 
virtual aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr getStateSpace () const=0
 
aikido::statespace::dart::MetaSkeletonStateSpacePtr getStateSpace ()
 
- Public Member Functions inherited from aikido::robot::Manipulator
virtual ~Manipulator ()=default
 
HandPtr getHand ()
 Returns the hand. More...
 
- Public Member Functions inherited from aikido::robot::Robot
virtual ~Robot ()=default
 
dart::dynamics::MetaSkeletonPtr getMetaSkeleton ()
 
aikido::statespace::dart::MetaSkeletonStateSpacePtr getStateSpace ()
 

Private Attributes

RobotPtr mRobot
 The robot whose metaSkeleton corresponds to this manipulator. More...
 
HandPtr mHand
 Hand of this manipulator. More...
 
util::VectorFieldPlannerParameters mVectorFieldParameters
 VectorFieldPlanenr-related parameters. More...
 
util::CRRTPlannerParameters mCRRTParameters
 CRRTPlanner-related parameters. More...
 

Detailed Description

A concrete implementation of a manipulator.

ConcreteManipulator supports a collection of end-effector specific planning methods.

Constructor & Destructor Documentation

◆ ConcreteManipulator()

aikido::robot::ConcreteManipulator::ConcreteManipulator ( RobotPtr  robot,
HandPtr  hand 
)

Constructor.

Parameters
[in]robotRobot corresponding to this manipulator.
[in]handHand of this manipulator.

◆ ~ConcreteManipulator()

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

Member Function Documentation

◆ executeTrajectory()

virtual std::future<void> aikido::robot::ConcreteManipulator::executeTrajectory ( const trajectory::TrajectoryPtr trajectory) const
overridevirtual

Executes a trajectory.

Parameters
[in]trajectoryTimed trajectory to execute

Implements aikido::robot::Robot.

◆ getFullCollisionConstraint()

virtual aikido::constraint::TestablePtr aikido::robot::ConcreteManipulator::getFullCollisionConstraint ( const statespace::dart::ConstMetaSkeletonStateSpacePtr space,
const dart::dynamics::MetaSkeletonPtr &  metaSkeleton,
const constraint::dart::CollisionFreePtr collisionFree 
) const
overridevirtual

TODO: Consider changing this to return a CollisionFreePtr.

Combines provided collision constraint with self collision constraint.

Parameters
[in]spaceSpace in which this collision constraint operates.
[in]metaSkeletonMetaskeleton for the statespace.
[in]collisionFreeCollision constraint.
Returns
Combined constraint.

Implements aikido::robot::Robot.

◆ getHand() [1/3]

HandPtr aikido::robot::Manipulator::getHand

Returns the hand.

◆ getHand() [2/3]

virtual ConstHandPtr aikido::robot::ConcreteManipulator::getHand ( ) const
overridevirtual

Returns the [const] hand.

Implements aikido::robot::Manipulator.

◆ getHand() [3/3]

virtual ConstHandPtr aikido::robot::Manipulator::getHand

Returns the [const] hand.

◆ getMetaSkeleton() [1/3]

dart::dynamics::MetaSkeletonPtr aikido::robot::Robot::getMetaSkeleton
Returns
MetaSkeleton of this robot.

◆ getMetaSkeleton() [2/3]

virtual dart::dynamics::ConstMetaSkeletonPtr aikido::robot::ConcreteManipulator::getMetaSkeleton ( ) const
overridevirtual
Returns
[const] MetaSkeleton of this robot.

Implements aikido::robot::Robot.

◆ getMetaSkeleton() [3/3]

virtual dart::dynamics::ConstMetaSkeletonPtr aikido::robot::Robot::getMetaSkeleton
Returns
[const] MetaSkeleton of this robot.

◆ getName()

virtual std::string aikido::robot::ConcreteManipulator::getName ( ) const
overridevirtual
Returns
Name of this Robot

Implements aikido::robot::Robot.

◆ getNamedConfiguration()

virtual boost::optional<Eigen::VectorXd> aikido::robot::ConcreteManipulator::getNamedConfiguration ( const std::string &  name) const
overridevirtual

Returns a named configuration.

Parameters
[in]nameName of the configuration
Returns
Configuration

Implements aikido::robot::Robot.

◆ getSelfCollisionConstraint()

virtual constraint::dart::CollisionFreePtr aikido::robot::ConcreteManipulator::getSelfCollisionConstraint ( const statespace::dart::ConstMetaSkeletonStateSpacePtr space,
const dart::dynamics::MetaSkeletonPtr &  metaSkeleton 
) const
overridevirtual

Returns self-collision constraint.

Parameters
[in]spaceSpace in which this collision constraint operates.
[in]metaSkeletonMetaskeleton for the statespace.

Implements aikido::robot::Robot.

◆ getStateSpace() [1/3]

aikido::statespace::dart::MetaSkeletonStateSpacePtr aikido::robot::Robot::getStateSpace
Returns
MetaSkeletonStateSpace of this robot.

◆ getStateSpace() [2/3]

virtual aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr aikido::robot::ConcreteManipulator::getStateSpace ( ) const
overridevirtual
Returns
[const] MetaSkeletonStateSpace of this robot.

Implements aikido::robot::Robot.

◆ getStateSpace() [3/3]

virtual aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr aikido::robot::Robot::getStateSpace
Returns
[const] MetaSkeletonStateSpace of this robot.

◆ planEndEffectorStraight()

trajectory::TrajectoryPtr aikido::robot::ConcreteManipulator::planEndEffectorStraight ( statespace::dart::MetaSkeletonStateSpacePtr space,
const dart::dynamics::MetaSkeletonPtr &  metaSkeleton,
const dart::dynamics::BodyNodePtr &  body,
const constraint::dart::CollisionFreePtr collisionFree,
double  distance,
double  timelimit,
double  positionTolerance,
double  angularTolerance 
)

TODO: Replace this with Problem interface.

Plans to a desired end-effector offset along the z axis of the end-effector.

Parameters
[in]spaceThe StateSpace for the metaskeleton.
[in]metaSkeletonMetaskeleton to plan with.
[in]bodyBodynode for the end-effector.
[in]collisionFreeCollisionFree constraint to check. Self-collision is checked by default.
[in]distanceDistance distance to move, in meters.
[in]timelimitTimelimit for plannnig.
[in]positionToleranceConstraint tolerance in meters.
[in]angularToleranceConstraint tolerance in radians.
Returns
Output trajectory

◆ planToEndEffectorOffset()

trajectory::TrajectoryPtr aikido::robot::ConcreteManipulator::planToEndEffectorOffset ( const statespace::dart::MetaSkeletonStateSpacePtr space,
const dart::dynamics::MetaSkeletonPtr &  metaSkeleton,
const dart::dynamics::BodyNodePtr &  body,
const constraint::dart::CollisionFreePtr collisionFree,
const Eigen::Vector3d &  direction,
double  distance,
double  timelimit,
double  positionTolerance,
double  angularTolerance 
)

TODO: Replace this with Problem interface.

Plans to a desired end-effector offset with fixed orientation.

Parameters
[in]spaceThe StateSpace for the metaskeleton.
[in]metaSkeletonMetaskeleton to plan with.
[in]bodyBodynode for the end-effector.
[in]collisionFreeCollisionFree constraint to check. Self-collision is checked by default.
[in]directionDirection unit vector in the world frame.
[in]distanceDistance distance to move, in meters.
[in]timelimitTimelimit for planning.
[in]positionToleranceConstraint tolerance in meters.
[in]angularToleranceConstraint tolerance in radians.
Returns
Output trajectory

◆ retimePath()

virtual std::unique_ptr<aikido::trajectory::Spline> aikido::robot::ConcreteManipulator::retimePath ( const dart::dynamics::MetaSkeletonPtr &  metaSkeleton,
const aikido::trajectory::Trajectory path 
)
overridevirtual

Returns a timed trajectory that can be executed by the robot.

Parameters
[in]metaSkeletonMetaskeleton of the path.
[in]pathGeometric path to execute.

Implements aikido::robot::Robot.

◆ retimePathWithKunz()

virtual std::unique_ptr<aikido::trajectory::Spline> aikido::robot::ConcreteManipulator::retimePathWithKunz ( const dart::dynamics::MetaSkeletonPtr &  metaSkeleton,
const aikido::trajectory::Trajectory path,
double  maxDeviation,
double  timestep 
)
overridevirtual

Returns a timed trajectory computed with KunzRetimer.

Parameters
[in]metaSkeletonMetaskeleton of the path.
[in]pathGeometric path to execute.
[in]maxDeviationMaximum deviation allowed from original path.
[in]timestepTime step between trajectory points.

Implements aikido::robot::Robot.

◆ setCRRTPlannerParameters()

void aikido::robot::ConcreteManipulator::setCRRTPlannerParameters ( const util::CRRTPlannerParameters crrtParameters)

TODO: This should be revisited once we have Planner API.

Sets CRRTPlanner parameters.

Parameters
[in]crrtParametersCRRT planner parameters

◆ setNamedConfigurations()

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

Sets the list of named configurations.

Parameters
[in]namedConfigurationsMap of name, configuration

Implements aikido::robot::Robot.

◆ setRoot()

virtual void aikido::robot::ConcreteManipulator::setRoot ( Robot robot)
overridevirtual

Sets the root of this robot.

Parameters
[in]robotParent robot

Implements aikido::robot::Robot.

◆ setVectorFieldPlannerParameters()

void aikido::robot::ConcreteManipulator::setVectorFieldPlannerParameters ( const util::VectorFieldPlannerParameters vfParameters)

TODO: This should be revisited once we have Planner API.

Sets VectorFieldPlanner parameters.

Parameters
[in]vfParametersVectorField Parameters

◆ smoothPath()

virtual std::unique_ptr<aikido::trajectory::Spline> aikido::robot::ConcreteManipulator::smoothPath ( const dart::dynamics::MetaSkeletonPtr &  metaSkeleton,
const aikido::trajectory::Trajectory path,
const constraint::TestablePtr constraint 
)
overridevirtual

Returns a timed trajectory that can be executed by the robot.

Parameters
[in]metaSkeletonMetaskeleton of the path.
[in]pathGeometric path to execute.
[in]constraintMust be satisfied after postprocessing. Typically collision constraint is passed.

Implements aikido::robot::Robot.

◆ step()

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

Simulates up to the provided timepoint.

Note
Assumes that the robot's skeleton is locked.
Parameters
[in]timepointTime to simulate to.

Implements aikido::robot::Robot.

Member Data Documentation

◆ mCRRTParameters

util::CRRTPlannerParameters aikido::robot::ConcreteManipulator::mCRRTParameters
private

CRRTPlanner-related parameters.

◆ mHand

HandPtr aikido::robot::ConcreteManipulator::mHand
private

Hand of this manipulator.

◆ mRobot

RobotPtr aikido::robot::ConcreteManipulator::mRobot
private

The robot whose metaSkeleton corresponds to this manipulator.

◆ mVectorFieldParameters

util::VectorFieldPlannerParameters aikido::robot::ConcreteManipulator::mVectorFieldParameters
private

VectorFieldPlanenr-related parameters.