Go to the documentation of this file.    1 #ifndef AIKIDO_ROBOT_CONCRETEMANIPULATOR_HPP_ 
    2 #define AIKIDO_ROBOT_CONCRETEMANIPULATOR_HPP_ 
   35   virtual std::unique_ptr<aikido::trajectory::Spline> 
smoothPath(
 
   36       const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
 
   41   virtual std::unique_ptr<aikido::trajectory::Spline> 
retimePath(
 
   42       const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
 
   47       const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
 
   50       double timestep) 
override;
 
   58       const std::string& name) 
const override;
 
   62       std::unordered_map<std::string, const Eigen::VectorXd>
 
   63           namedConfigurations) 
override;
 
   66   virtual std::string 
getName() 
const override;
 
   69   virtual dart::dynamics::ConstMetaSkeletonPtr 
getMetaSkeleton() 
const override;
 
   80       const std::chrono::system_clock::time_point& timepoint) 
override;
 
   85       const dart::dynamics::MetaSkeletonPtr& metaSkeleton) 
const override;
 
   90       const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
 
  108       const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
 
  109       const dart::dynamics::BodyNodePtr& body,
 
  111       const Eigen::Vector3d& direction,
 
  114       double positionTolerance,
 
  115       double angularTolerance);
 
  132       const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
 
  133       const dart::dynamics::BodyNodePtr& body,
 
  137       double positionTolerance,
 
  138       double angularTolerance);
 
  169 #endif // AIKIDO_ROBOT_CONCRETEMANIPULATOR_HPP_ 
 
 
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
 
virtual dart::dynamics::ConstMetaSkeletonPtr getMetaSkeleton() const =0
 
std::shared_ptr< MetaSkeletonStateSpace > MetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
 
virtual aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr getStateSpace() const override
 
virtual void setRoot(Robot *robot) override
Sets the root of this robot.
 
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
 
virtual std::string getName() const override
 
virtual constraint::dart::CollisionFreePtr getSelfCollisionConstraint(const statespace::dart::ConstMetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton) const override
Returns self-collision constraint.
 
virtual void setNamedConfigurations(std::unordered_map< std::string, const Eigen::VectorXd > namedConfigurations) override
Sets the list of named configurations.
 
std::shared_ptr< Robot > RobotPtr
Definition: Robot.hpp:21
 
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.
 
virtual ConstHandPtr getHand() const =0
Returns the [const] hand.
 
virtual boost::optional< Eigen::VectorXd > getNamedConfiguration(const std::string &name) const override
Returns a named configuration.
 
void setCRRTPlannerParameters(const util::CRRTPlannerParameters &crrtParameters)
TODO: This should be revisited once we have Planner API.
 
virtual std::future< void > executeTrajectory(const trajectory::TrajectoryPtr &trajectory) const override
Executes a trajectory.
 
std::shared_ptr< CollisionFree > CollisionFreePtr
Definition: CollisionFree.hpp:22
 
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.
 
std::shared_ptr< Trajectory > TrajectoryPtr
Definition: Trajectory.hpp:13
 
A concrete implementation of a manipulator.
Definition: ConcreteManipulator.hpp:16
 
virtual dart::dynamics::ConstMetaSkeletonPtr getMetaSkeleton() const override
 
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.
 
virtual void step(const std::chrono::system_clock::time_point &timepoint) override
Simulates up to the provided timepoint.
 
Base interface for manipulator.
Definition: Manipulator.hpp:14
 
ConcreteManipulator(RobotPtr robot, HandPtr hand)
Constructor.
 
void setVectorFieldPlannerParameters(const util::VectorFieldPlannerParameters &vfParameters)
TODO: This should be revisited once we have Planner API.
 
util::CRRTPlannerParameters mCRRTParameters
CRRTPlanner-related parameters.
Definition: ConcreteManipulator.hpp:163
 
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.
 
std::shared_ptr< Hand > HandPtr
Definition: Hand.hpp:17
 
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.
 
virtual ~ConcreteManipulator()=default
 
Robot interface for defining basic behaviors of a robot.
Definition: Robot.hpp:26
 
HandPtr mHand
Hand of this manipulator.
Definition: ConcreteManipulator.hpp:157
 
RobotPtr mRobot
The robot whose metaSkeleton corresponds to this manipulator.
Definition: ConcreteManipulator.hpp:154
 
util::VectorFieldPlannerParameters mVectorFieldParameters
VectorFieldPlanenr-related parameters.
Definition: ConcreteManipulator.hpp:160
 
std::shared_ptr< Testable > TestablePtr
Definition: Testable.hpp:13
 
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.
 
#define AIKIDO_DECLARE_POINTERS(X)
Definition: pointers.hpp:21
 
Time-parameterized path in a StateSpace.
Definition: Trajectory.hpp:20
 
virtual aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr getStateSpace() const =0
 
std::shared_ptr< const Hand > ConstHandPtr
Definition: Hand.hpp:17
 
virtual ConstHandPtr getHand() const override
Returns the [const] hand.