#include <fsrobo_r_joint_trajectory_action.h>
Public Member Functions | |
FSRoboRJointTrajectoryAction () | |
Constructor. More... | |
void | run () |
Begin processing messages and publishing topics. More... | |
~FSRoboRJointTrajectoryAction () | |
Destructor. More... | |
Private Types | |
typedef actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction > | JointTractoryActionServer |
Private Member Functions | |
void | abortGoal () |
Aborts the current action goal and sends a stop command (empty message) to the robot driver. More... | |
void | cancelCB (JointTractoryActionServer::GoalHandle gh) |
Action server cancel callback method. More... | |
bool | cancelMotionCB (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res) |
Cancel motion callback (executed when cancel_motion service is called) More... | |
void | controllerStateCB (const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg) |
Controller state callback (executed when feedback message received) More... | |
void | goalCB (JointTractoryActionServer::GoalHandle gh) |
Action server goal callback method. More... | |
void | robotStatusCB (const industrial_msgs::RobotStatusConstPtr &msg) |
Controller status callback (executed when robot status message received) More... | |
void | watchdog (const ros::TimerEvent &e) |
Watch dog callback, used to detect robot driver failures. More... | |
bool | withinGoalConstraints (const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg, const trajectory_msgs::JointTrajectory &traj) |
Controller status callback (executed when robot status message received) More... | |
Private Attributes | |
JointTractoryActionServer | action_server_ |
Internal action server. More... | |
JointTractoryActionServer::GoalHandle | active_goal_ |
Cache of the current active goal. More... | |
bool | controller_alive_ |
Controller was alive during the last watchdog interval. More... | |
trajectory_msgs::JointTrajectory | current_traj_ |
Cache of the current active trajectory. More... | |
double | goal_threshold_ |
The goal joint threshold used for determining if a robot is near it final destination. A single value is used for all joints. More... | |
bool | has_active_goal_ |
Indicates action has an active goal. More... | |
bool | has_moved_once_ |
Indicates that the robot has been in a moving state at least once since starting the current active trajectory. More... | |
std::vector< std::string > | joint_names_ |
The joint names associated with the robot the action is interfacing with. The joint names must be the same as expected by the robot driver. More... | |
industrial_msgs::RobotStatusConstPtr | last_robot_status_ |
Cache of the last subscribed status message. More... | |
control_msgs::FollowJointTrajectoryFeedbackConstPtr | last_trajectory_state_ |
Cache of the last subscribed feedback message. More... | |
ros::NodeHandle | node_ |
Internal ROS node handle. More... | |
ros::Publisher | pub_trajectory_command_ |
Publishes desired trajectory (typically to the robot driver) More... | |
ros::ServiceServer | srv_cancel_motion_ |
Service to stop robot motion. More... | |
ros::Subscriber | sub_robot_status_ |
Subscribes to the robot status (typically published by the robot driver). More... | |
ros::Subscriber | sub_trajectory_state_ |
Subscribes to trajectory feedback (typically published by the robot driver). More... | |
ros::Time | time_to_check_ |
Time at which to start checking for completion of current goal, if one is active. More... | |
ros::Timer | watchdog_timer_ |
Watchdog time used to fail the action request if the robot driver is not responding. More... | |
Static Private Attributes | |
static const double | DEFAULT_GOAL_THRESHOLD_ = 0.01 |
The default goal joint threshold see(goal_threshold). Unit are joint specific (i.e. radians or meters). More... | |
static const double | WATCHDOG_PERIOD_ = 1.0 |
The watchdog period (seconds) More... | |
Definition at line 46 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Definition at line 69 of file fsrobo_r_joint_trajectory_action.h.
fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::FSRoboRJointTrajectoryAction | ( | ) |
Constructor.
Definition at line 42 of file fsrobo_r_joint_trajectory_action.cpp.
fsrobo_r_driver::joint_trajectory_action::FSRoboRJointTrajectoryAction::~FSRoboRJointTrajectoryAction | ( | ) |
Destructor.
Definition at line 69 of file fsrobo_r_joint_trajectory_action.cpp.
|
private |
Aborts the current action goal and sends a stop command (empty message) to the robot driver.
Definition at line 300 of file fsrobo_r_joint_trajectory_action.cpp.
|
private |
Action server cancel callback method.
gh | goal handle |
Definition at line 193 of file fsrobo_r_joint_trajectory_action.cpp.
|
private |
Cancel motion callback (executed when cancel_motion service is called)
req | service request |
res | service response |
Definition at line 285 of file fsrobo_r_joint_trajectory_action.cpp.
|
private |
Controller state callback (executed when feedback message received)
msg | joint trajectory feedback message |
Definition at line 213 of file fsrobo_r_joint_trajectory_action.cpp.
|
private |
Action server goal callback method.
gh | goal handle |
Definition at line 116 of file fsrobo_r_joint_trajectory_action.cpp.
|
private |
Controller status callback (executed when robot status message received)
msg | robot status message |
Definition at line 73 of file fsrobo_r_joint_trajectory_action.cpp.
|
inline |
Begin processing messages and publishing topics.
Definition at line 65 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Watch dog callback, used to detect robot driver failures.
e | time event information |
Definition at line 86 of file fsrobo_r_joint_trajectory_action.cpp.
|
private |
Controller status callback (executed when robot status message received)
msg | trajectory feedback message |
traj | trajectory to test against feedback |
Definition at line 311 of file fsrobo_r_joint_trajectory_action.cpp.
|
private |
Internal action server.
Definition at line 79 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Cache of the current active goal.
Definition at line 128 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Controller was alive during the last watchdog interval.
Definition at line 112 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Cache of the current active trajectory.
Definition at line 132 of file fsrobo_r_joint_trajectory_action.h.
|
staticprivate |
The default goal joint threshold see(goal_threshold). Unit are joint specific (i.e. radians or meters).
Definition at line 138 of file fsrobo_r_joint_trajectory_action.h.
|
private |
The goal joint threshold used for determining if a robot is near it final destination. A single value is used for all joints.
NOTE: This value is used in conjunction with the robot inMotion status (see industrial_msgs::RobotStatus) if it exists.
Definition at line 147 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Indicates action has an active goal.
Definition at line 117 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Indicates that the robot has been in a moving state at least once since starting the current active trajectory.
Definition at line 123 of file fsrobo_r_joint_trajectory_action.h.
|
private |
The joint names associated with the robot the action is interfacing with. The joint names must be the same as expected by the robot driver.
Definition at line 154 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Cache of the last subscribed status message.
Definition at line 164 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Cache of the last subscribed feedback message.
Definition at line 159 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Internal ROS node handle.
Definition at line 74 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Publishes desired trajectory (typically to the robot driver)
Definition at line 84 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Service to stop robot motion.
Definition at line 101 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Subscribes to the robot status (typically published by the robot driver).
Definition at line 96 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Subscribes to trajectory feedback (typically published by the robot driver).
Definition at line 90 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Time at which to start checking for completion of current goal, if one is active.
Definition at line 170 of file fsrobo_r_joint_trajectory_action.h.
|
staticprivate |
The watchdog period (seconds)
Definition at line 175 of file fsrobo_r_joint_trajectory_action.h.
|
private |
Watchdog time used to fail the action request if the robot driver is not responding.
Definition at line 107 of file fsrobo_r_joint_trajectory_action.h.