#include <RobotTrajectoryExecutor.h>
Public Types | |
enum | ExecStatus { RUNNING, SUCCEEDED, PREEMPTED, TIMED_OUT, ABORTED, FAILED, UNKNOWN } |
typedef ExecStatus | ExecutionStatus |
typedef actionlib::SimpleActionClient < control_msgs::FollowJointTrajectoryAction > | FollowJointTrajectoryActionClient |
typedef path_navigation_msgs::PathExecutionGoal | PathGoal |
typedef path_navigation_msgs::PathExecutionResult | PathGoalResult |
typedef path_navigation_msgs::PathExecutionResultConstPtr | PathGoalResultConstPtr |
typedef actionlib::SimpleActionClient < path_navigation_msgs::PathExecutionAction > | PathNavigationActionClient |
typedef control_msgs::FollowJointTrajectoryGoal | TrajectoryGoal |
typedef control_msgs::FollowJointTrajectoryResult | TrajectoryGoalResult |
Public Member Functions | |
bool | cancelExecution () |
ExecutionStatus | getLastExecutionStatus () |
RobotTrajectoryExecutor (const std::string &_virtual_joint_name, const std::string _trajectory_action_topic, const std::string _path_action_topic) | |
bool | sendTrajectory (const moveit_msgs::RobotTrajectory &t) |
bool | waitForExecution (const ros::Duration &timeout) |
~RobotTrajectoryExecutor () | |
Private Member Functions | |
bool | clientsConnected () |
bool | connectClients () |
bool | hasTrajectoryServer () const |
void | pathDoneCB (const actionlib::SimpleClientGoalState &state, const PathGoalResultConstPtr &result) |
RobotTrajectoryExecutor (const RobotTrajectoryExecutor &other) | |
bool | sendNavigationActionRequest (const std::vector< geometry_msgs::Transform > &transforms, const std::string &transforms_frame_id, const float waitForResult, const std::vector< ros::Duration > ×=std::vector< ros::Duration >()) |
bool | sendNavigationActionRequest (const nav_msgs::Path &p, const std::string &transforms_frame_id, const float waitForResult=-1) |
bool | sendTrajectoryActionRequest (const trajectory_msgs::JointTrajectory &trajectory, float waitForResult=-1) |
void | setLastStateFrom (const actionlib::SimpleClientGoalState &state) |
void | trajectoryDoneCB (const actionlib::SimpleClientGoalState &state, const control_msgs::FollowJointTrajectoryResultConstPtr &result) |
Private Attributes | |
trajectory_msgs::JointTrajectory | current_trajectory |
bool | has_current_request |
bool | has_current_trajectory |
bool | has_path_navigator |
bool | has_trajectory_executor |
FollowJointTrajectoryActionClient * | joint_trajectory_action_client |
ExecutionStatus | last_exec |
boost::mutex | lock |
std::string | path_action_topic |
PathNavigationActionClient * | path_navigation_action_client |
bool | path_running |
std::string | trajectory_action_topic |
bool | trajectory_running |
std::string | virtual_joint_name |
Executes a moveit_msgs/RobotTrajectory and takes the MultiDOF information from the virtual joint to make the robot navigate to that location.
So far, multi DOF trajectories (the virtual joint trajectories) are supported in the following way: Only 1 virtual joint is allowed, which specifies the robot navigation path. It is not executedin parallel to the arm's JointTrajectory though, as it probably is intended to. The arm's joint trajectory is only executed AFTER the robot has navigated along the path. This has to be changed later, a simple solution would be to take the trajectories apart into single points and send them in parallel to navigation and arm movement.
Definition at line 35 of file RobotTrajectoryExecutor.h.
Definition at line 50 of file RobotTrajectoryExecutor.h.
typedef actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> moveit_controller_multidof::RobotTrajectoryExecutor::FollowJointTrajectoryActionClient |
Definition at line 37 of file RobotTrajectoryExecutor.h.
typedef path_navigation_msgs::PathExecutionGoal moveit_controller_multidof::RobotTrajectoryExecutor::PathGoal |
Definition at line 39 of file RobotTrajectoryExecutor.h.
typedef path_navigation_msgs::PathExecutionResult moveit_controller_multidof::RobotTrajectoryExecutor::PathGoalResult |
Definition at line 40 of file RobotTrajectoryExecutor.h.
typedef path_navigation_msgs::PathExecutionResultConstPtr moveit_controller_multidof::RobotTrajectoryExecutor::PathGoalResultConstPtr |
Definition at line 41 of file RobotTrajectoryExecutor.h.
typedef actionlib::SimpleActionClient<path_navigation_msgs::PathExecutionAction> moveit_controller_multidof::RobotTrajectoryExecutor::PathNavigationActionClient |
Definition at line 38 of file RobotTrajectoryExecutor.h.
typedef control_msgs::FollowJointTrajectoryGoal moveit_controller_multidof::RobotTrajectoryExecutor::TrajectoryGoal |
Definition at line 43 of file RobotTrajectoryExecutor.h.
typedef control_msgs::FollowJointTrajectoryResult moveit_controller_multidof::RobotTrajectoryExecutor::TrajectoryGoalResult |
Definition at line 44 of file RobotTrajectoryExecutor.h.
Definition at line 47 of file RobotTrajectoryExecutor.h.
RobotTrajectoryExecutor::RobotTrajectoryExecutor | ( | const std::string & | _virtual_joint_name, |
const std::string | _trajectory_action_topic, | ||
const std::string | _path_action_topic | ||
) |
_virtual_joint_name | name of the virtual joint. If empty, then only execution of joint trajectories (no navigation) will be supported. |
_trajectory_action_topic | the action topic onto which to forward the joint trajectory |
_path_action_topic | the action topic onto which to forward the path navigation. This can be empty if _virtual_joint_name is empty as well and the robot is not mobile. |
Definition at line 9 of file RobotTrajectoryExecutor.cpp.
Definition at line 85 of file RobotTrajectoryExecutor.cpp.
RobotTrajectoryExecutor::RobotTrajectoryExecutor | ( | const RobotTrajectoryExecutor & | other | ) | [private] |
Definition at line 60 of file RobotTrajectoryExecutor.cpp.
Definition at line 190 of file RobotTrajectoryExecutor.cpp.
bool RobotTrajectoryExecutor::clientsConnected | ( | ) | [private] |
Definition at line 413 of file RobotTrajectoryExecutor.cpp.
bool RobotTrajectoryExecutor::connectClients | ( | ) | [private] |
Definition at line 421 of file RobotTrajectoryExecutor.cpp.
Definition at line 408 of file RobotTrajectoryExecutor.cpp.
bool RobotTrajectoryExecutor::hasTrajectoryServer | ( | ) | const [private] |
Definition at line 91 of file RobotTrajectoryExecutor.cpp.
void RobotTrajectoryExecutor::pathDoneCB | ( | const actionlib::SimpleClientGoalState & | state, |
const PathGoalResultConstPtr & | result | ||
) | [private] |
Definition at line 252 of file RobotTrajectoryExecutor.cpp.
bool RobotTrajectoryExecutor::sendNavigationActionRequest | ( | const std::vector< geometry_msgs::Transform > & | transforms, |
const std::string & | transforms_frame_id, | ||
const float | waitForResult, | ||
const std::vector< ros::Duration > & | times = std::vector<ros::Duration>() |
||
) | [private] |
Definition at line 344 of file RobotTrajectoryExecutor.cpp.
bool RobotTrajectoryExecutor::sendNavigationActionRequest | ( | const nav_msgs::Path & | p, |
const std::string & | transforms_frame_id, | ||
const float | waitForResult = -1 |
||
) | [private] |
Definition at line 361 of file RobotTrajectoryExecutor.cpp.
bool RobotTrajectoryExecutor::sendTrajectory | ( | const moveit_msgs::RobotTrajectory & | t | ) |
Definition at line 96 of file RobotTrajectoryExecutor.cpp.
bool RobotTrajectoryExecutor::sendTrajectoryActionRequest | ( | const trajectory_msgs::JointTrajectory & | trajectory, |
float | waitForResult = -1 |
||
) | [private] |
Definition at line 299 of file RobotTrajectoryExecutor.cpp.
void RobotTrajectoryExecutor::setLastStateFrom | ( | const actionlib::SimpleClientGoalState & | state | ) | [private] |
Definition at line 458 of file RobotTrajectoryExecutor.cpp.
void RobotTrajectoryExecutor::trajectoryDoneCB | ( | const actionlib::SimpleClientGoalState & | state, |
const control_msgs::FollowJointTrajectoryResultConstPtr & | result | ||
) | [private] |
Definition at line 284 of file RobotTrajectoryExecutor.cpp.
bool RobotTrajectoryExecutor::waitForExecution | ( | const ros::Duration & | timeout | ) |
Definition at line 214 of file RobotTrajectoryExecutor.cpp.
trajectory_msgs::JointTrajectory moveit_controller_multidof::RobotTrajectoryExecutor::current_trajectory [private] |
Definition at line 116 of file RobotTrajectoryExecutor.h.
Definition at line 113 of file RobotTrajectoryExecutor.h.
Definition at line 114 of file RobotTrajectoryExecutor.h.
Definition at line 110 of file RobotTrajectoryExecutor.h.
Definition at line 111 of file RobotTrajectoryExecutor.h.
FollowJointTrajectoryActionClient* moveit_controller_multidof::RobotTrajectoryExecutor::joint_trajectory_action_client [private] |
Definition at line 107 of file RobotTrajectoryExecutor.h.
Definition at line 124 of file RobotTrajectoryExecutor.h.
boost::mutex moveit_controller_multidof::RobotTrajectoryExecutor::lock [private] |
Definition at line 122 of file RobotTrajectoryExecutor.h.
std::string moveit_controller_multidof::RobotTrajectoryExecutor::path_action_topic [private] |
Definition at line 105 of file RobotTrajectoryExecutor.h.
PathNavigationActionClient* moveit_controller_multidof::RobotTrajectoryExecutor::path_navigation_action_client [private] |
Definition at line 108 of file RobotTrajectoryExecutor.h.
Definition at line 118 of file RobotTrajectoryExecutor.h.
std::string moveit_controller_multidof::RobotTrajectoryExecutor::trajectory_action_topic [private] |
Definition at line 104 of file RobotTrajectoryExecutor.h.
Definition at line 119 of file RobotTrajectoryExecutor.h.
std::string moveit_controller_multidof::RobotTrajectoryExecutor::virtual_joint_name [private] |
Definition at line 126 of file RobotTrajectoryExecutor.h.