Go to the documentation of this file. 1 #ifndef AIKIDO_CONTROL_ROS_ROSJOINTCOMMANDEXECUTOR_HPP_
2 #define AIKIDO_CONTROL_ROS_ROSJOINTCOMMANDEXECUTOR_HPP_
24 template <ExecutorType T>
35 const ::ros::NodeHandle& node,
36 const std::string& controllerName,
37 const std::vector<dart::dynamics::DegreeOfFreedom*>& dofs,
38 std::chrono::milliseconds connectionTimeout
40 std::chrono::milliseconds connectionPollingPeriod
47 const std::vector<double>& command,
48 const std::chrono::duration<double>& timeout,
49 const std::chrono::system_clock::time_point& timepoint)
override;
52 void step(
const std::chrono::system_clock::time_point& timepoint)
override;
75 #endif // ifndef AIKIDO_CONTROL_ROS_ROSJOINTCOMMANDEXECUTOR_HPP_
Abstract class for executing a command of a single type on a group of joints.
Definition: JointCommandExecutor.hpp:21
void cancel() override
Cancels the current command.
Definition: RosJointCommandExecutor-impl.hpp:79
void step(const std::chrono::system_clock::time_point &timepoint) override
Step to a point in time.
Definition: RosJointCommandExecutor-impl.hpp:71
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
This class uses actionlib to command an action of the type pr_control_msgs/JointGroupCommandAction.
Definition: RosJointGroupCommandClient.hpp:22
constexpr int DEFAULT_CON_TIMEOUT_MS
Default actionlib client connection timeout (ms)
Definition: RosJointCommandExecutor.hpp:16
RosJointGroupCommandClient mClient
Definition: RosJointCommandExecutor.hpp:58
constexpr int DEFAULT_POLL_PERIOD_MS
Default actionlib client polling period (ms)
Definition: RosJointCommandExecutor.hpp:19
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
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
virtual ~RosJointCommandExecutor()
Definition: RosJointCommandExecutor-impl.hpp:47
This Executor uses pr_control_msgs/JointGroupCommandAction to execute joint-wise commands.
Definition: RosJointCommandExecutor.hpp:25