32 #ifndef JOINT_TRAJTORY_ACTION_H 33 #define JOINT_TRAJTORY_ACTION_H 38 #include <trajectory_msgs/JointTrajectory.h> 39 #include <control_msgs/FollowJointTrajectoryAction.h> 40 #include <control_msgs/FollowJointTrajectoryFeedback.h> 41 #include <industrial_msgs/RobotStatus.h> 45 namespace joint_trajectory_action
210 void controllerStateCB(
const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg);
219 void robotStatusCB(
const industrial_msgs::RobotStatusConstPtr &msg);
240 const trajectory_msgs::JointTrajectory & traj);
~JointTrajectoryAction()
Destructor.
void robotStatusCB(const industrial_msgs::RobotStatusConstPtr &msg)
Controller status callback (executed when robot status message received)
void watchdog(const ros::TimerEvent &e)
Watch dog callback, used to detect robot driver failures.
ServerGoalHandle< control_msgs::FollowJointTrajectoryAction > GoalHandle
JointTractoryActionServer action_server_
Internal action server.
ROSCPP_DECL void spin(Spinner &spinner)
ros::Publisher pub_trajectory_command_
Publishes desired trajectory (typically to the robot driver)
control_msgs::FollowJointTrajectoryFeedbackConstPtr last_trajectory_state_
Cache of the last subscribed feedback message.
industrial_msgs::RobotStatusConstPtr last_robot_status_
Cache of the last subscribed status message.
bool has_active_goal_
Indicates action has an active goal.
std::string name_
Name of this class, for logging namespacing.
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.
std::vector< std::string > joint_names_
The joint names associated with the robot the action is interfacing with. The joint names must be the...
static const double WATCHDOG_PERIOD_
The watchdog period (seconds)
ros::NodeHandle node_
Internal ROS node handle.
static const double DEFAULT_GOAL_THRESHOLD_
The default goal joint threshold see(goal_threshold). Unit are joint specific (i.e. radians or meters).
actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction > JointTractoryActionServer
bool controller_alive_
Controller was alive during the last watchdog interval.
ros::Subscriber sub_robot_status_
Subscribes to the robot status (typically published by the robot driver).
ros::Timer watchdog_timer_
Watchdog time used to fail the action request if the robot driver is not responding.
ros::Subscriber sub_trajectory_state_
Subscribes to trajectory feedback (typically published by the robot driver).
void abortGoal()
Aborts the current action goal and sends a stop command (empty message) to the robot driver...
bool has_moved_once_
Indicates that the robot has been in a moving state at least once since starting the current active t...
JointTrajectoryAction()
Constructor.
void cancelCB(JointTractoryActionServer::GoalHandle gh)
Action server cancel callback method.
bool withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg, const trajectory_msgs::JointTrajectory &traj)
Controller status callback (executed when robot status message received)
JointTractoryActionServer::GoalHandle active_goal_
Cache of the current active goal.
void run()
Begin processing messages and publishing topics.
trajectory_msgs::JointTrajectory current_traj_
Cache of the current active trajectory.
void controllerStateCB(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg)
Controller state callback (executed when feedback message received)
void goalCB(JointTractoryActionServer::GoalHandle gh)
Action server goal callback method.
ros::Time time_to_check_
Time at which to start checking for completion of current goal, if one is active. ...