joint_trajectory_action.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Southwest Research Institute
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in the
14  * documentation and/or other materials provided with the distribution.
15  * * Neither the name of the Southwest Research Institute, nor the names
16  * of its contributors may be used to endorse or promote products derived
17  * from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef JOINT_TRAJTORY_ACTION_H
33 #define JOINT_TRAJTORY_ACTION_H
34 
35 #include <ros/ros.h>
37 
38 #include <trajectory_msgs/JointTrajectory.h>
39 #include <control_msgs/FollowJointTrajectoryAction.h>
40 #include <control_msgs/FollowJointTrajectoryFeedback.h>
41 #include <industrial_msgs/RobotStatus.h>
42 
44 {
45 namespace joint_trajectory_action
46 {
47 
49 {
50 
51 public:
57 
63 
67  void run() { ros::spin(); }
68 
69 private:
70 
72 
76  std::string name_;
77 
82 
86  JointTractoryActionServer action_server_;
87 
92 
98 
104 
110 
115 
120 
126 
134  trajectory_msgs::JointTrajectory current_traj_;
135 
140  static const double DEFAULT_GOAL_THRESHOLD_;// = 0.01;
141 
150 
156  std::vector<std::string> joint_names_;
157 
161  control_msgs::FollowJointTrajectoryFeedbackConstPtr last_trajectory_state_;
162 
166  industrial_msgs::RobotStatusConstPtr last_robot_status_;
167 
173 
177  static const double WATCHDOG_PERIOD_;// = 1.0;
178 
185  void watchdog(const ros::TimerEvent &e);
186 
194 
210  void controllerStateCB(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg);
211 
219  void robotStatusCB(const industrial_msgs::RobotStatusConstPtr &msg);
220 
227  void abortGoal();
228 
239  bool withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
240  const trajectory_msgs::JointTrajectory & traj);
241 };
242 
243 } //joint_trajectory_action
244 } //industrial_robot_client
245 
246 #endif /* JOINT_TRAJTORY_ACTION_H */
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
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.
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 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...
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. ...


industrial_robot_client
Author(s): Jeremy Zoss
autogenerated on Sat Sep 21 2019 03:30:13