Go to the documentation of this file. 1 #ifndef AIKIDO_CONTROL_ROS_ROSPOSITIONCOMMANDEXECUTOR_HPP_
2 #define AIKIDO_CONTROL_ROS_ROSPOSITIONCOMMANDEXECUTOR_HPP_
9 #include <actionlib/client/action_client.h>
10 #include <pr_control_msgs/SetPositionAction.h>
11 #include <ros/callback_queue.h>
13 #include <sensor_msgs/JointState.h>
35 ::ros::NodeHandle node,
36 const std::string& serverName,
37 std::vector<std::string> jointNames,
38 std::chrono::milliseconds connectionTimeout
39 = std::chrono::milliseconds{1000},
40 std::chrono::milliseconds connectionPollingPeriod
41 = std::chrono::milliseconds{20});
47 std::future<void>
execute(
const Eigen::VectorXd& goalPositions)
override;
53 void step(
const std::chrono::system_clock::time_point& timepoint)
override;
57 = actionlib::ActionClient<pr_control_msgs::SetPositionAction>;
83 #endif // ifndef AIKIDO_CONTROL_ROS_ROSPOSITIONCOMMANDEXECUTOR_HPP_
void transitionCallback(GoalHandle handle)
std::future< void > execute(const Eigen::VectorXd &goalPositions) override
Sends positions to ROS server for execution.
std::vector< std::string > mJointNames
Definition: RosPositionCommandExecutor.hpp:67
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
RosPositionActionClient::GoalHandle mGoalHandle
Definition: RosPositionCommandExecutor.hpp:65
std::mutex mMutex
Manages access to mInProgress, mPromise.
Definition: RosPositionCommandExecutor.hpp:76
bool mInProgress
Definition: RosPositionCommandExecutor.hpp:72
RosPositionCommandExecutor(::ros::NodeHandle node, const std::string &serverName, std::vector< std::string > jointNames, std::chrono::milliseconds connectionTimeout=std::chrono::milliseconds{1000}, std::chrono::milliseconds connectionPollingPeriod=std::chrono::milliseconds{20})
Constructor.
void step(const std::chrono::system_clock::time_point &timepoint) override
Step to a point in time.
virtual ~RosPositionCommandExecutor()
Abstract class for executing position commands.
Definition: PositionCommandExecutor.hpp:23
This class uses actionlib to command an action of the type pr_control_msgs/SetPosition.
Definition: RosPositionCommandExecutor.hpp:24
std::unique_ptr< std::promise< void > > mPromise
Definition: RosPositionCommandExecutor.hpp:73
std::chrono::milliseconds mConnectionPollingPeriod
Definition: RosPositionCommandExecutor.hpp:70
::ros::NodeHandle mNode
Definition: RosPositionCommandExecutor.hpp:62
RosPositionActionClient::GoalHandle GoalHandle
Definition: RosPositionCommandExecutor.hpp:58
actionlib::ActionClient< pr_control_msgs::SetPositionAction > RosPositionActionClient
Definition: RosPositionCommandExecutor.hpp:57
::ros::CallbackQueue mCallbackQueue
Definition: RosPositionCommandExecutor.hpp:63
RosPositionActionClient mClient
Definition: RosPositionCommandExecutor.hpp:64
std::chrono::milliseconds mConnectionTimeout
Definition: RosPositionCommandExecutor.hpp:69