Aikido
|
This class uses actionlib to command an action of the type pr_control_msgs/SetPosition. More...
#include <aikido/control/ros/RosPositionCommandExecutor.hpp>
Public Member Functions | |
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. More... | |
virtual | ~RosPositionCommandExecutor () |
std::future< void > | execute (const Eigen::VectorXd &goalPositions) override |
Sends positions to ROS server for execution. More... | |
void | step (const std::chrono::system_clock::time_point &timepoint) override |
Step to a point in time. More... | |
![]() | |
virtual | ~PositionCommandExecutor ()=default |
Private Types | |
using | RosPositionActionClient = actionlib::ActionClient< pr_control_msgs::SetPositionAction > |
using | GoalHandle = RosPositionActionClient::GoalHandle |
Private Member Functions | |
void | transitionCallback (GoalHandle handle) |
Private Attributes | |
::ros::NodeHandle | mNode |
::ros::CallbackQueue | mCallbackQueue |
RosPositionActionClient | mClient |
RosPositionActionClient::GoalHandle | mGoalHandle |
std::vector< std::string > | mJointNames |
std::chrono::milliseconds | mConnectionTimeout |
std::chrono::milliseconds | mConnectionPollingPeriod |
bool | mInProgress |
std::unique_ptr< std::promise< void > > | mPromise |
std::mutex | mMutex |
Manages access to mInProgress, mPromise. More... | |
Additional Inherited Members | |
![]() | |
std::chrono::system_clock::time_point | mTimeOfPreviousCall |
Time of previous call to step . More... | |
This class uses actionlib to command an action of the type pr_control_msgs/SetPosition.
It specifies a set of target positions and sends it to the ROS server for execution
|
private |
|
private |
aikido::control::ros::RosPositionCommandExecutor::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.
[in] | node | ROS node handle for action client. |
[in] | serverName | Name of the server to send trajectory to. |
[in] | jointNames | The names of the joints to set position targets for |
[in] | connectionTimeout | Timeout for server connection. |
[in] | connectionPollingPeriod | Polling period for server connection. |
|
virtual |
|
overridevirtual |
Sends positions to ROS server for execution.
[in] | goalPositions | Vector of target positions for each joint |
Implements aikido::control::PositionCommandExecutor.
|
overridevirtual |
Step to a point in time.
timepoint
can be a time in the future to enable faster than real-time execution.timepoint | Time to simulate to |
To be executed on a separate thread. Regularly checks for the completion of a sent trajectory.
Implements aikido::control::PositionCommandExecutor.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
mutableprivate |
Manages access to mInProgress, mPromise.
|
private |
|
private |