|
Aikido
|
A concrete implementation of a manipulator. More...
#include <aikido/robot/ConcreteManipulator.hpp>
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::Spline > | smoothPath (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::Spline > | retimePath (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::Spline > | retimePathWithKunz (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... | |
A concrete implementation of a manipulator.
ConcreteManipulator supports a collection of end-effector specific planning methods.
|
virtualdefault |
|
overridevirtual |
Executes a trajectory.
| [in] | trajectory | Timed trajectory to execute |
Implements aikido::robot::Robot.
|
overridevirtual |
TODO: Consider changing this to return a CollisionFreePtr.
Combines provided collision constraint with self collision constraint.
| [in] | space | Space in which this collision constraint operates. |
| [in] | metaSkeleton | Metaskeleton for the statespace. |
| [in] | collisionFree | Collision constraint. |
Implements aikido::robot::Robot.
| HandPtr aikido::robot::Manipulator::getHand |
Returns the hand.
|
overridevirtual |
Returns the [const] hand.
Implements aikido::robot::Manipulator.
| virtual ConstHandPtr aikido::robot::Manipulator::getHand |
Returns the [const] hand.
| dart::dynamics::MetaSkeletonPtr aikido::robot::Robot::getMetaSkeleton |
|
overridevirtual |
Implements aikido::robot::Robot.
| virtual dart::dynamics::ConstMetaSkeletonPtr aikido::robot::Robot::getMetaSkeleton |
|
overridevirtual |
Implements aikido::robot::Robot.
|
overridevirtual |
Returns a named configuration.
| [in] | name | Name of the configuration |
Implements aikido::robot::Robot.
|
overridevirtual |
Returns self-collision constraint.
| [in] | space | Space in which this collision constraint operates. |
| [in] | metaSkeleton | Metaskeleton for the statespace. |
Implements aikido::robot::Robot.
| aikido::statespace::dart::MetaSkeletonStateSpacePtr aikido::robot::Robot::getStateSpace |
|
overridevirtual |
Implements aikido::robot::Robot.
| virtual aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr aikido::robot::Robot::getStateSpace |
| 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.
| [in] | space | The StateSpace for the metaskeleton. |
| [in] | metaSkeleton | Metaskeleton to plan with. |
| [in] | body | Bodynode for the end-effector. |
| [in] | collisionFree | CollisionFree constraint to check. Self-collision is checked by default. |
| [in] | distance | Distance distance to move, in meters. |
| [in] | timelimit | Timelimit for plannnig. |
| [in] | positionTolerance | Constraint tolerance in meters. |
| [in] | angularTolerance | Constraint tolerance in radians. |
| 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.
| [in] | space | The StateSpace for the metaskeleton. |
| [in] | metaSkeleton | Metaskeleton to plan with. |
| [in] | body | Bodynode for the end-effector. |
| [in] | collisionFree | CollisionFree constraint to check. Self-collision is checked by default. |
| [in] | direction | Direction unit vector in the world frame. |
| [in] | distance | Distance distance to move, in meters. |
| [in] | timelimit | Timelimit for planning. |
| [in] | positionTolerance | Constraint tolerance in meters. |
| [in] | angularTolerance | Constraint tolerance in radians. |
|
overridevirtual |
Returns a timed trajectory that can be executed by the robot.
| [in] | metaSkeleton | Metaskeleton of the path. |
| [in] | path | Geometric path to execute. |
Implements aikido::robot::Robot.
|
overridevirtual |
Returns a timed trajectory computed with KunzRetimer.
| [in] | metaSkeleton | Metaskeleton of the path. |
| [in] | path | Geometric path to execute. |
| [in] | maxDeviation | Maximum deviation allowed from original path. |
| [in] | timestep | Time step between trajectory points. |
Implements aikido::robot::Robot.
| void aikido::robot::ConcreteManipulator::setCRRTPlannerParameters | ( | const util::CRRTPlannerParameters & | crrtParameters | ) |
TODO: This should be revisited once we have Planner API.
Sets CRRTPlanner parameters.
| [in] | crrtParameters | CRRT planner parameters |
|
overridevirtual |
Sets the list of named configurations.
| [in] | namedConfigurations | Map of name, configuration |
Implements aikido::robot::Robot.
|
overridevirtual |
| void aikido::robot::ConcreteManipulator::setVectorFieldPlannerParameters | ( | const util::VectorFieldPlannerParameters & | vfParameters | ) |
TODO: This should be revisited once we have Planner API.
Sets VectorFieldPlanner parameters.
| [in] | vfParameters | VectorField Parameters |
|
overridevirtual |
Returns a timed trajectory that can be executed by the robot.
| [in] | metaSkeleton | Metaskeleton of the path. |
| [in] | path | Geometric path to execute. |
| [in] | constraint | Must be satisfied after postprocessing. Typically collision constraint is passed. |
Implements aikido::robot::Robot.
|
overridevirtual |
Simulates up to the provided timepoint.
| [in] | timepoint | Time to simulate to. |
Implements aikido::robot::Robot.
|
private |
CRRTPlanner-related parameters.
|
private |
The robot whose metaSkeleton corresponds to this manipulator.
|
private |
VectorFieldPlanenr-related parameters.