Aikido
RosJointCommandExecutor.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_CONTROL_ROS_ROSJOINTCOMMANDEXECUTOR_HPP_
2 #define AIKIDO_CONTROL_ROS_ROSJOINTCOMMANDEXECUTOR_HPP_
3 
4 #include <chrono>
5 #include <future>
6 #include <set>
7 
10 
11 namespace aikido {
12 namespace control {
13 namespace ros {
14 
16 constexpr int DEFAULT_CON_TIMEOUT_MS{1000};
17 
19 constexpr int DEFAULT_POLL_PERIOD_MS{20};
20 
24 template <ExecutorType T>
26 {
27 public:
35  const ::ros::NodeHandle& node,
36  const std::string& controllerName,
37  const std::vector<dart::dynamics::DegreeOfFreedom*>& dofs,
38  std::chrono::milliseconds connectionTimeout
39  = std::chrono::milliseconds{DEFAULT_CON_TIMEOUT_MS},
40  std::chrono::milliseconds connectionPollingPeriod
41  = std::chrono::milliseconds{DEFAULT_POLL_PERIOD_MS});
42 
43  virtual ~RosJointCommandExecutor();
44 
45  // Documentation inherited.
46  std::future<int> execute(
47  const std::vector<double>& command,
48  const std::chrono::duration<double>& timeout,
49  const std::chrono::system_clock::time_point& timepoint) override;
50 
51  // Documentation inherited.
52  void step(const std::chrono::system_clock::time_point& timepoint) override;
53 
54  // Documentation inherited.
55  void cancel() override;
56 
57 private:
59 };
60 
61 // Define common executors
62 
68 
69 } // namespace ros
70 } // namespace control
71 } // namespace aikido
72 
74 
75 #endif // ifndef AIKIDO_CONTROL_ROS_ROSJOINTCOMMANDEXECUTOR_HPP_
aikido::control::JointCommandExecutor
Abstract class for executing a command of a single type on a group of joints.
Definition: JointCommandExecutor.hpp:21
aikido::control::ros::RosJointCommandExecutor::cancel
void cancel() override
Cancels the current command.
Definition: RosJointCommandExecutor-impl.hpp:79
RosJointGroupCommandClient.hpp
aikido::control::ros::RosJointCommandExecutor::step
void step(const std::chrono::system_clock::time_point &timepoint) override
Step to a point in time.
Definition: RosJointCommandExecutor-impl.hpp:71
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::control::ros::RosJointGroupCommandClient
This class uses actionlib to command an action of the type pr_control_msgs/JointGroupCommandAction.
Definition: RosJointGroupCommandClient.hpp:22
aikido::control::ros::DEFAULT_CON_TIMEOUT_MS
constexpr int DEFAULT_CON_TIMEOUT_MS
Default actionlib client connection timeout (ms)
Definition: RosJointCommandExecutor.hpp:16
aikido::control::ros::RosJointCommandExecutor::mClient
RosJointGroupCommandClient mClient
Definition: RosJointCommandExecutor.hpp:58
aikido::control::ros::DEFAULT_POLL_PERIOD_MS
constexpr int DEFAULT_POLL_PERIOD_MS
Default actionlib client polling period (ms)
Definition: RosJointCommandExecutor.hpp:19
JointCommandExecutor.hpp
aikido::control::ros::RosJointCommandExecutor::RosJointCommandExecutor
RosJointCommandExecutor(const ::ros::NodeHandle &node, const std::string &controllerName, const std::vector< dart::dynamics::DegreeOfFreedom * > &dofs, std::chrono::milliseconds connectionTimeout=std::chrono::milliseconds{DEFAULT_CON_TIMEOUT_MS}, std::chrono::milliseconds connectionPollingPeriod=std::chrono::milliseconds{DEFAULT_POLL_PERIOD_MS})
Constructor.
Definition: RosJointCommandExecutor-impl.hpp:26
aikido::control::ros::RosJointCommandExecutor::execute
std::future< int > execute(const std::vector< double > &command, const std::chrono::duration< double > &timeout, const std::chrono::system_clock::time_point &timepoint) override
Execute a Joint Command, setting future upon completion.
Definition: RosJointCommandExecutor-impl.hpp:54
RosJointCommandExecutor-impl.hpp
aikido::control::ros::RosJointCommandExecutor::~RosJointCommandExecutor
virtual ~RosJointCommandExecutor()
Definition: RosJointCommandExecutor-impl.hpp:47
aikido::control::ros::RosJointCommandExecutor
This Executor uses pr_control_msgs/JointGroupCommandAction to execute joint-wise commands.
Definition: RosJointCommandExecutor.hpp:25