Aikido
TrajectoryExecutor.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_CONTROL_TRAJECTORYEXECUTOR_HPP_
2 #define AIKIDO_CONTROL_TRAJECTORYEXECUTOR_HPP_
3 
4 #include <chrono>
5 #include <future>
6 #include <set>
7 
8 #include <dart/dart.hpp>
9 
12 #include "aikido/control/util.hpp"
14 
15 namespace aikido {
16 namespace control {
17 
19 
20 class TrajectoryExecutor : public Executor
22 {
23 public:
29  const std::vector<dart::dynamics::DegreeOfFreedom*>& dofs,
30  const std::set<ExecutorType> otherTypes = std::set<ExecutorType>(),
31  const std::chrono::milliseconds threadRate = defaultThreadRate)
32  : Executor(
34  std::set<ExecutorType>{ExecutorType::TRAJECTORY}, otherTypes),
35  dofs,
36  threadRate)
37  {
38  }
39  virtual ~TrajectoryExecutor() = default;
40 
44  virtual void validate(const trajectory::Trajectory* traj) = 0;
45 
53  virtual std::future<void> execute(const trajectory::ConstTrajectoryPtr& traj)
54  = 0;
55 
56  // Documentation inherited.
57  virtual void step(
58  const std::chrono::system_clock::time_point& timepoint) override = 0;
59 
61  virtual void cancel() = 0;
62 
63 protected:
65  std::set<const trajectory::Trajectory*> mValidatedTrajectories;
66 
68  std::chrono::system_clock::time_point mExecutionStartTime;
69 };
70 
71 } // namespace control
72 } // namespace aikido
73 
74 #endif
aikido::control::ExecutorType::TRAJECTORY
@ TRAJECTORY
util.hpp
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::control::TrajectoryExecutor::cancel
virtual void cancel()=0
Cancel the current trajectory.
aikido::control::TrajectoryExecutor::~TrajectoryExecutor
virtual ~TrajectoryExecutor()=default
aikido::trajectory::ConstTrajectoryPtr
std::shared_ptr< const Trajectory > ConstTrajectoryPtr
Definition: Trajectory.hpp:13
aikido::control::TrajectoryExecutor::validate
virtual void validate(const trajectory::Trajectory *traj)=0
Validate the traj in preparation for execution.
aikido::control::TrajectoryExecutor::execute
virtual std::future< void > execute(const trajectory::ConstTrajectoryPtr &traj)=0
Validate and execute traj, setting future upon completion.
aikido::control::TrajectoryExecutor::TrajectoryExecutor
TrajectoryExecutor(const std::vector< dart::dynamics::DegreeOfFreedom * > &dofs, const std::set< ExecutorType > otherTypes=std::set< ExecutorType >(), const std::chrono::milliseconds threadRate=defaultThreadRate)
Constructor Documentation Inherited.
Definition: TrajectoryExecutor.hpp:28
aikido::control::TrajectoryExecutor::step
virtual void step(const std::chrono::system_clock::time_point &timepoint) override=0
Step to a point in time.
aikido::control::concatenateTypes
std::set< ExecutorType > concatenateTypes(std::set< ExecutorType > first, std::set< ExecutorType > second)
Concatenate two sets of ExecutorTypes Useful for initializer-list constructors.
Definition: util.hpp:29
Executor.hpp
pointers.hpp
Trajectory.hpp
aikido::control::TrajectoryExecutor
Abstract class for executing trajectories.
Definition: TrajectoryExecutor.hpp:21
aikido::control::TrajectoryExecutor::mValidatedTrajectories
std::set< const trajectory::Trajectory * > mValidatedTrajectories
Set of trajectories validated by executor.
Definition: TrajectoryExecutor.hpp:65
aikido::control::TrajectoryExecutor::mExecutionStartTime
std::chrono::system_clock::time_point mExecutionStartTime
Time of previous call.
Definition: TrajectoryExecutor.hpp:68
aikido::control::defaultThreadRate
constexpr std::chrono::milliseconds defaultThreadRate
Default rate for ExecutorThread to call step()
Definition: Executor.hpp:47
aikido::control::ExecutorType
ExecutorType
Type of executor Can be used to determine if 2 executors make conflicting demands of individual degre...
Definition: Executor.hpp:35
aikido::control::Executor
Abstract class for executing commands on degrees of freedom.
Definition: Executor.hpp:50
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