Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #ifndef MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_TRAJECTORY_ACTION_H
00034 #define MOTOMAN_DRIVER_INDUSTRIAL_ROBOT_CLIENT_JOINT_TRAJECTORY_ACTION_H
00035
00036 #include <map>
00037 #include <vector>
00038 #include <string>
00039
00040 #include <ros/ros.h>
00041 #include <actionlib/server/action_server.h>
00042
00043 #include <trajectory_msgs/JointTrajectory.h>
00044 #include <control_msgs/FollowJointTrajectoryAction.h>
00045 #include <control_msgs/FollowJointTrajectoryFeedback.h>
00046 #include <industrial_msgs/RobotStatus.h>
00047 #include <motoman_driver/industrial_robot_client/robot_group.h>
00048 #include <motoman_msgs/DynamicJointTrajectory.h>
00049 namespace industrial_robot_client
00050 {
00051 namespace joint_trajectory_action
00052 {
00053
00054 class JointTrajectoryAction
00055 {
00056 public:
00061 JointTrajectoryAction();
00062
00067 ~JointTrajectoryAction();
00068
00072 bool init();
00073 void run()
00074 {
00075 ros::spin();
00076 }
00077
00078 private:
00079 typedef actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> JointTractoryActionServer;
00080
00084 ros::NodeHandle node_;
00085 actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction>* actionServer_;
00086
00090 JointTractoryActionServer action_server_;
00091
00095 ros::Publisher pub_trajectory_command_;
00096
00097 std::map<int, ros::Publisher> pub_trajectories_;
00098
00099 std::map<int, RobotGroup> robot_groups_;
00100
00105 ros::Subscriber sub_trajectory_state_;
00106
00107 std::map<int, ros::Subscriber> sub_trajectories_;
00108
00113 ros::Subscriber sub_robot_status_;
00114
00115 std::map<int, ros::Subscriber> sub_status_;
00116
00117 std::map<int, JointTractoryActionServer*> act_servers_;
00122 ros::Timer watchdog_timer_;
00123
00124 std::map<int, ros::Timer>watchdog_timer_map_;
00125
00129 bool has_active_goal_;
00130
00131 std::map<int, bool> has_active_goal_map_;
00132
00136 JointTractoryActionServer::GoalHandle active_goal_;
00137
00138 std::map<int, JointTractoryActionServer::GoalHandle> active_goal_map_;
00142 trajectory_msgs::JointTrajectory current_traj_;
00143
00144 std::map<int, trajectory_msgs::JointTrajectory> current_traj_map_;
00145
00146 std::vector<std::string> all_joint_names_;
00147
00152 static const double DEFAULT_GOAL_THRESHOLD_;
00153
00161 double goal_threshold_;
00162
00168 std::vector<std::string> joint_names_;
00169
00173 control_msgs::FollowJointTrajectoryFeedbackConstPtr last_trajectory_state_;
00174
00175 std::map<int, control_msgs::FollowJointTrajectoryFeedbackConstPtr> last_trajectory_state_map_;
00176
00181 bool trajectory_state_recvd_;
00182
00183 std::map<int, bool> trajectory_state_recvd_map_;
00184
00188 industrial_msgs::RobotStatusConstPtr last_robot_status_;
00189
00193 static const double WATCHD0G_PERIOD_;
00194
00201 void watchdog(const ros::TimerEvent &e);
00202
00203 void watchdog(const ros::TimerEvent &e, int group_number);
00204
00212 void goalCB(JointTractoryActionServer::GoalHandle gh);
00213
00221 void cancelCB(JointTractoryActionServer::GoalHandle gh);
00230 void goalCB(JointTractoryActionServer::GoalHandle gh, int group_number);
00231
00239 void cancelCB(JointTractoryActionServer::GoalHandle gh, int group_number);
00247 void controllerStateCB(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg);
00248
00249 void controllerStateCB(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg, int robot_id);
00250
00251
00259 void robotStatusCB(const industrial_msgs::RobotStatusConstPtr &msg);
00260
00267 void abortGoal();
00268
00269 void abortGoal(int robot_id);
00270
00281 bool withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
00282 const trajectory_msgs::JointTrajectory & traj);
00283
00284 bool withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
00285 const trajectory_msgs::JointTrajectory & traj, int robot_id);
00286
00287 bool withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
00288 const motoman_msgs::DynamicJointTrajectory & traj);
00289 };
00290
00291 }
00292 }
00293
00294 #endif
00295