Aikido
ConcreteRobot.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_ROBOT_CONCRETEROBOT_HPP_
2 #define AIKIDO_ROBOT_CONCRETEROBOT_HPP_
3 
4 #include <chrono>
5 #include <string>
6 #include <unordered_map>
7 
8 #include <Eigen/Core>
9 #include <dart/dart.hpp>
10 
12 #include "aikido/common/RNG.hpp"
19 #include "aikido/robot/Robot.hpp"
20 #include "aikido/robot/util.hpp"
23 
24 namespace aikido {
25 namespace robot {
26 
28 
29 class ConcreteRobot : public Robot
30 {
31 public:
32  // Expose base class functions
35 
45  const std::string& name,
46  dart::dynamics::MetaSkeletonPtr metaSkeleton,
47  bool simulation,
49  aikido::control::TrajectoryExecutorPtr trajectoryExecutor,
50  dart::collision::CollisionDetectorPtr collisionDetector,
51  std::shared_ptr<dart::collision::BodyNodeCollisionFilter>
52  selfCollisionFilter);
53 
54  virtual ~ConcreteRobot() = default;
55 
56  // Documentation inherited.
57  virtual std::future<void> executeTrajectory(
58  const trajectory::TrajectoryPtr& trajectory) const override;
59 
60  // Documentation inherited.
61  virtual boost::optional<Eigen::VectorXd> getNamedConfiguration(
62  const std::string& name) const override;
63 
64  // Documentation inherited.
65  virtual void setNamedConfigurations(
66  std::unordered_map<std::string, const Eigen::VectorXd>
67  namedConfigurations) override;
68 
69  // Documentation inherited.
70  virtual std::string getName() const override;
71 
72  // Documentation inherited.
73  virtual dart::dynamics::ConstMetaSkeletonPtr getMetaSkeleton() const override;
74 
75  // Documentation inherited.
77  getStateSpace() const override;
78 
79  // Documentation inherited.
80  virtual void setRoot(Robot* robot) override;
81 
82  // Documentation inherited.
83  virtual void step(
84  const std::chrono::system_clock::time_point& timepoint) override;
85 
86  // Documentation inherited.
87  virtual aikido::constraint::dart::CollisionFreePtr getSelfCollisionConstraint(
89  const dart::dynamics::MetaSkeletonPtr& metaSkeleton) const override;
90 
91  // Documentation inherited.
92  virtual aikido::constraint::TestablePtr getFullCollisionConstraint(
94  const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
95  const constraint::dart::CollisionFreePtr& collisionFree) const override;
96 
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;
107 
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;
120 
128  template <typename PostProcessor>
129  aikido::trajectory::UniqueSplinePtr postProcessPath(
130  const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
131  const aikido::trajectory::Trajectory* path,
132  const constraint::TestablePtr& constraint,
133  const typename PostProcessor::Params& postProcessorParams);
134 
143  template <typename PostProcessor>
144  aikido::trajectory::UniqueSplinePtr postProcessPath(
145  const Eigen::VectorXd& velocityLimits,
146  const Eigen::VectorXd& accelerationLimits,
147  const aikido::trajectory::Trajectory* path,
148  const constraint::TestablePtr& constraint,
149  const typename PostProcessor::Params& postProcessorParams);
150 
162  const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
163  const aikido::statespace::StateSpace::State* goalState,
164  const aikido::constraint::dart::CollisionFreePtr& collisionFree,
165  double timelimit);
166 
179  const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
180  const Eigen::VectorXd& goal,
181  const aikido::constraint::dart::CollisionFreePtr& collisionFree,
182  double timelimit);
183 
195  const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
196  const std::vector<aikido::statespace::StateSpace::State*>& goalStates,
197  const aikido::constraint::dart::CollisionFreePtr& collisionFree,
198  double timelimit);
199 
211  const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
212  const std::vector<Eigen::VectorXd>& goals,
213  const aikido::constraint::dart::CollisionFreePtr& collisionFree,
214  double timelimit);
215 
231  const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
232  const dart::dynamics::BodyNodePtr& bodyNode,
234  const aikido::constraint::dart::CollisionFreePtr& collisionFree,
235  double timelimit,
236  std::size_t maxNumTrials,
237  const distance::ConstConfigurationRankerPtr& ranker = nullptr);
238 
253  const dart::dynamics::MetaSkeletonPtr& metaSkeleton,
254  const dart::dynamics::BodyNodePtr& bodyNode,
255  const aikido::constraint::dart::TSRPtr& goalTsr,
256  const aikido::constraint::dart::TSRPtr& constraintTsr,
257  const aikido::constraint::dart::CollisionFreePtr& collisionFree,
258  double timelimit);
259 
265  aikido::trajectory::TrajectoryPtr planToNamedConfiguration(
266  const std::string& name,
267  const aikido::constraint::dart::CollisionFreePtr& collisionFree,
268  double timelimit);
269 
273  void setCRRTPlannerParameters(
274  const util::CRRTPlannerParameters& crrtParameters);
275 
280  Eigen::VectorXd getVelocityLimits(
281  const dart::dynamics::MetaSkeleton& metaSkeleton) const;
282 
287  Eigen::VectorXd getAccelerationLimits(
288  const dart::dynamics::MetaSkeleton& metaSkeleton) const;
289 
290 private:
291  // Named Configurations are read from a YAML file
292  using ConfigurationMap
293  = std::unordered_map<std::string, const Eigen::VectorXd>;
294 
295  std::unique_ptr<aikido::common::RNG> cloneRNG();
296 
300 
302  std::string mName;
303 
305  dart::dynamics::MetaSkeletonPtr mMetaSkeleton;
307 
309  dart::dynamics::SkeletonPtr mParentSkeleton;
310 
312  // bool mSimulation;
313  // TODO(JS): Disabled since not used in this class
314 
315  std::unique_ptr<common::RNG> mRng;
316 
317  std::shared_ptr<control::TrajectoryExecutor> mTrajectoryExecutor;
318 
319  // double mCollisionResolution;
320  // TODO(JS): Disabled since not used in this class
321 
324 
325  ::dart::collision::CollisionDetectorPtr mCollisionDetector;
326  std::shared_ptr<dart::collision::BodyNodeCollisionFilter>
328 
330 };
331 
332 } // namespace robot
333 } // namespace aikido
334 
336 
337 #endif // AIKIDO_ROBOT_CONCRETEROBOT_HPP_
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido::common::UniqueRNGPtr
std::unique_ptr< RNG > UniqueRNGPtr
Definition: RNG.hpp:17
aikido::robot::Robot::getMetaSkeleton
virtual dart::dynamics::ConstMetaSkeletonPtr getMetaSkeleton() const =0
aikido::robot::ConcreteRobot::ConfigurationMap
std::unordered_map< std::string, const Eigen::VectorXd > ConfigurationMap
Definition: ConcreteRobot.hpp:293
aikido::statespace::dart::MetaSkeletonStateSpacePtr
std::shared_ptr< MetaSkeletonStateSpace > MetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido::robot::ConcreteRobot
Definition: ConcreteRobot.hpp:29
RNG.hpp
ConfigurationRanker.hpp
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::robot::ConcreteRobot::mCollisionDetector
::dart::collision::CollisionDetectorPtr mCollisionDetector
Definition: ConcreteRobot.hpp:325
aikido::robot::ConcreteRobot::mName
std::string mName
Name of this robot.
Definition: ConcreteRobot.hpp:302
aikido::robot::util::planToConfiguration
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.
aikido::constraint::dart::TSRPtr
std::shared_ptr< TSR > TSRPtr
Definition: TSR.hpp:17
aikido::robot::util::planToTSR
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.
TSR.hpp
util.hpp
aikido::robot::util::planToConfigurations
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.
aikido::robot::ConcreteRobot::mNamedConfigurations
ConfigurationMap mNamedConfigurations
Commonly used configurations.
Definition: ConcreteRobot.hpp:323
aikido::constraint::dart::CollisionFreePtr
std::shared_ptr< CollisionFree > CollisionFreePtr
Definition: CollisionFree.hpp:22
aikido::trajectory::TrajectoryPtr
std::shared_ptr< Trajectory > TrajectoryPtr
Definition: Trajectory.hpp:13
aikido::robot::ConcreteRobot::mCRRTParameters
util::CRRTPlannerParameters mCRRTParameters
Definition: ConcreteRobot.hpp:329
ParabolicSmoother.hpp
aikido::robot::util::CRRTPlannerParameters
Definition: util.hpp:63
CollisionFree.hpp
aikido::robot::ConcreteRobot::mMetaSkeleton
dart::dynamics::MetaSkeletonPtr mMetaSkeleton
MetaSkeleton of this robot.
Definition: ConcreteRobot.hpp:305
aikido::distance::ConstConfigurationRankerPtr
std::shared_ptr< const ConfigurationRanker > ConstConfigurationRankerPtr
Definition: ConfigurationRanker.hpp:13
aikido::robot::ConcreteRobot::mRng
std::unique_ptr< common::RNG > mRng
True if running in simulation mode.
Definition: ConcreteRobot.hpp:315
aikido::robot::ConcreteRobot::mStateSpace
statespace::dart::MetaSkeletonStateSpacePtr mStateSpace
Definition: ConcreteRobot.hpp:306
Trajectory.hpp
aikido::robot::util::planToTSRwithTrajectoryConstraint
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...
aikido::robot::ConcreteRobot::mTrajectoryExecutor
std::shared_ptr< control::TrajectoryExecutor > mTrajectoryExecutor
Definition: ConcreteRobot.hpp:317
Robot.hpp
aikido::control::TrajectoryExecutorPtr
std::shared_ptr< TrajectoryExecutor > TrajectoryExecutorPtr
Definition: TrajectoryExecutor.hpp:14
aikido::trajectory::UniqueSplinePtr
std::unique_ptr< Spline > UniqueSplinePtr
Definition: Spline.hpp:10
MetaSkeletonStateSpace.hpp
aikido::robot::ConcreteRobot::mRootRobot
Robot * mRootRobot
If this robot belongs to another (Composite)Robot, mRootRobot is the topmost robot containing this ro...
Definition: ConcreteRobot.hpp:299
aikido::robot::Robot
Robot interface for defining basic behaviors of a robot.
Definition: Robot.hpp:26
ConcreteRobot-impl.hpp
ParabolicTimer.hpp
aikido::robot::ConcreteRobot::mSelfCollisionFilter
std::shared_ptr< dart::collision::BodyNodeCollisionFilter > mSelfCollisionFilter
Definition: ConcreteRobot.hpp:327
ExecutorThread.hpp
aikido::statespace::StateSpace::State
Definition: StateSpace.hpp:167
aikido::constraint::TestablePtr
std::shared_ptr< Testable > TestablePtr
Definition: Testable.hpp:13
aikido::robot::ConcreteRobot::mParentSkeleton
dart::dynamics::SkeletonPtr mParentSkeleton
Skeleton containing mRobot.
Definition: ConcreteRobot.hpp:309
TrajectoryExecutor.hpp
AIKIDO_DECLARE_POINTERS
#define AIKIDO_DECLARE_POINTERS(X)
Definition: pointers.hpp:21
aikido::trajectory::Trajectory
Time-parameterized path in a StateSpace.
Definition: Trajectory.hpp:20
aikido::robot::Robot::getStateSpace
virtual aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr getStateSpace() const =0