Go to the documentation of this file. 1 #ifndef AIKIDO_ROBOT_CONCRETEROBOT_HPP_
2 #define AIKIDO_ROBOT_CONCRETEROBOT_HPP_
6 #include <unordered_map>
9 #include <dart/dart.hpp>
45 const std::string& name,
46 dart::dynamics::MetaSkeletonPtr metaSkeleton,
50 dart::collision::CollisionDetectorPtr collisionDetector,
51 std::shared_ptr<dart::collision::BodyNodeCollisionFilter>
57 virtual std::future<void> executeTrajectory(
61 virtual boost::optional<Eigen::VectorXd> getNamedConfiguration(
62 const std::string& name)
const override;
65 virtual void setNamedConfigurations(
66 std::unordered_map<std::string, const Eigen::VectorXd>
67 namedConfigurations)
override;
70 virtual std::string getName()
const override;
73 virtual dart::dynamics::ConstMetaSkeletonPtr getMetaSkeleton()
const override;
77 getStateSpace()
const override;
80 virtual void setRoot(
Robot* robot)
override;
84 const std::chrono::system_clock::time_point& timepoint)
override;
89 const dart::dynamics::MetaSkeletonPtr& metaSkeleton)
const override;
94 const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
102 template <
typename PostProcessor>
103 std::shared_ptr<aikido::planner::TrajectoryPostProcessor>
104 getTrajectoryPostProcessor(
105 const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
106 const typename PostProcessor::Params& postProcessorParams)
const;
114 template <
typename PostProcessor>
115 std::shared_ptr<aikido::planner::TrajectoryPostProcessor>
116 getTrajectoryPostProcessor(
117 const Eigen::VectorXd& velocityLimits,
118 const Eigen::VectorXd& accelerationLimits,
119 const typename PostProcessor::Params& postProcessorParams)
const;
128 template <
typename PostProcessor>
130 const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
133 const typename PostProcessor::Params& postProcessorParams);
143 template <
typename PostProcessor>
145 const Eigen::VectorXd& velocityLimits,
146 const Eigen::VectorXd& accelerationLimits,
149 const typename PostProcessor::Params& postProcessorParams);
162 const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
179 const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
180 const Eigen::VectorXd& goal,
195 const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
196 const std::vector<aikido::statespace::StateSpace::State*>& goalStates,
211 const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
212 const std::vector<Eigen::VectorXd>& goals,
231 const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
232 const dart::dynamics::BodyNodePtr& bodyNode,
236 std::size_t maxNumTrials,
253 const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
254 const dart::dynamics::BodyNodePtr& bodyNode,
266 const std::string& name,
273 void setCRRTPlannerParameters(
280 Eigen::VectorXd getVelocityLimits(
281 const dart::dynamics::MetaSkeleton& metaSkeleton)
const;
287 Eigen::VectorXd getAccelerationLimits(
288 const dart::dynamics::MetaSkeleton& metaSkeleton)
const;
293 = std::unordered_map<std::string, const Eigen::VectorXd>;
295 std::unique_ptr<aikido::common::RNG> cloneRNG();
315 std::unique_ptr<common::RNG>
mRng;
326 std::shared_ptr<dart::collision::BodyNodeCollisionFilter>
337 #endif // AIKIDO_ROBOT_CONCRETEROBOT_HPP_
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
std::unique_ptr< RNG > UniqueRNGPtr
Definition: RNG.hpp:17
virtual dart::dynamics::ConstMetaSkeletonPtr getMetaSkeleton() const =0
std::unordered_map< std::string, const Eigen::VectorXd > ConfigurationMap
Definition: ConcreteRobot.hpp:293
std::shared_ptr< MetaSkeletonStateSpace > MetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
Definition: ConcreteRobot.hpp:29
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
::dart::collision::CollisionDetectorPtr mCollisionDetector
Definition: ConcreteRobot.hpp:325
std::string mName
Name of this robot.
Definition: ConcreteRobot.hpp:302
trajectory::TrajectoryPtr planToConfiguration(const statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const statespace::StateSpace::State *goalState, const constraint::TestablePtr &collisionTestable, common::RNG *rng, double timelimit)
Plan the robot to a specific configuration.
std::shared_ptr< TSR > TSRPtr
Definition: TSR.hpp:17
trajectory::TrajectoryPtr planToTSR(const statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const dart::dynamics::BodyNodePtr &bodyNode, const constraint::dart::TSRPtr &tsr, const constraint::TestablePtr &collisionTestable, common::RNG *rng, double timelimit, std::size_t maxNumTrials, const distance::ConstConfigurationRankerPtr &ranker=nullptr)
Plan the configuration of the metakeleton such that the specified bodynode is set to a sample in TSR.
trajectory::TrajectoryPtr planToConfigurations(const statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const std::vector< statespace::StateSpace::State * > &goalStates, const constraint::TestablePtr &collisionTestable, common::RNG *rng, double timelimit)
Plan the robot to a set of configurations.
ConfigurationMap mNamedConfigurations
Commonly used configurations.
Definition: ConcreteRobot.hpp:323
std::shared_ptr< CollisionFree > CollisionFreePtr
Definition: CollisionFree.hpp:22
std::shared_ptr< Trajectory > TrajectoryPtr
Definition: Trajectory.hpp:13
util::CRRTPlannerParameters mCRRTParameters
Definition: ConcreteRobot.hpp:329
dart::dynamics::MetaSkeletonPtr mMetaSkeleton
MetaSkeleton of this robot.
Definition: ConcreteRobot.hpp:305
std::shared_ptr< const ConfigurationRanker > ConstConfigurationRankerPtr
Definition: ConfigurationRanker.hpp:13
std::unique_ptr< common::RNG > mRng
True if running in simulation mode.
Definition: ConcreteRobot.hpp:315
statespace::dart::MetaSkeletonStateSpacePtr mStateSpace
Definition: ConcreteRobot.hpp:306
trajectory::InterpolatedPtr planToTSRwithTrajectoryConstraint(const statespace::dart::MetaSkeletonStateSpacePtr &space, const dart::dynamics::MetaSkeletonPtr &metaSkeleton, const dart::dynamics::BodyNodePtr &bodyNode, const constraint::dart::TSRPtr &goalTsr, const constraint::dart::TSRPtr &constraintTsr, const constraint::TestablePtr &collisionTestable, double timelimit, const CRRTPlannerParameters &crrtParameters=CRRTPlannerParameters())
Returns a Trajectory that moves the configuration of the metakeleton such that the specified bodynode...
std::shared_ptr< control::TrajectoryExecutor > mTrajectoryExecutor
Definition: ConcreteRobot.hpp:317
std::shared_ptr< TrajectoryExecutor > TrajectoryExecutorPtr
Definition: TrajectoryExecutor.hpp:14
std::unique_ptr< Spline > UniqueSplinePtr
Definition: Spline.hpp:10
Robot * mRootRobot
If this robot belongs to another (Composite)Robot, mRootRobot is the topmost robot containing this ro...
Definition: ConcreteRobot.hpp:299
Robot interface for defining basic behaviors of a robot.
Definition: Robot.hpp:26
std::shared_ptr< dart::collision::BodyNodeCollisionFilter > mSelfCollisionFilter
Definition: ConcreteRobot.hpp:327
Definition: StateSpace.hpp:167
std::shared_ptr< Testable > TestablePtr
Definition: Testable.hpp:13
dart::dynamics::SkeletonPtr mParentSkeleton
Skeleton containing mRobot.
Definition: ConcreteRobot.hpp:309
#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