trajectory_execution_monitor.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2011, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00037 #include <ros/ros.h>
00038 #include <boost/function.hpp>
00039 #include <trajectory_msgs/JointTrajectory.h>
00040 #include <trajectory_execution_monitor/trajectory_recorder.h>
00041 #include <trajectory_execution_monitor/trajectory_controller_handler.h>
00042 #include <planning_environment/models/collision_models.h>
00043 
00044 namespace trajectory_execution_monitor
00045 {
00046 
00048 struct TrajectoryExecutionRequest {
00049   
00050   std::string group_name_;
00051   std::string controller_name_;
00052   std::string recorder_name_;
00053 
00054   bool monitor_overshoot_;
00055   double max_overshoot_velocity_epsilon_;
00056   ros::Duration min_overshoot_time_;
00057   ros::Duration max_overshoot_time_;
00058 
00059   bool failure_ok_;
00060   bool test_for_close_enough_;
00061   double max_joint_distance_;
00062   double failure_time_factor_;
00063   
00064   trajectory_msgs::JointTrajectory trajectory_;
00065   boost::function<void(const std::string& group_name)> callback_function_;
00066 
00067   TrajectoryExecutionRequest();
00068 };
00069 
00071 enum TrajectoryExecutionResult {
00072   NOT_ATTEMPTED = 0,
00073   SUCCEEDED,
00074   NO_RECORDER,
00075   NO_HANDLER,
00076   ALREADY_AT_GOAL,
00077   HANDLER_FAILED_ENTIRELY,
00078   HANDLER_REPORTS_FAILURE,
00079   HANDLER_REPORTS_FAILURE_BUT_OK,
00080   HANDLER_REPORTS_FAILURE_BUT_CLOSE_ENOUGH
00081 };
00082 
00084 struct TrajectoryExecutionData {
00085 
00087   TrajectoryExecutionResult result_;
00088 
00090   trajectory_msgs::JointTrajectory recorded_trajectory_;
00093   trajectory_msgs::JointTrajectory overshoot_trajectory_;
00094 
00096   ros::Duration time_;
00098   ros::Duration overshoot_time_;
00101   double angular_distance_;                                     // recorded
00102 };
00103 
00105 struct TrajectoryExecutionDataVector : public std::vector<TrajectoryExecutionData> 
00106 {
00107 
00108   void reset() {
00109     clear();
00110     last_attempted_trajectory_index_ = 0;
00111   }
00112 
00113   unsigned int last_attempted_trajectory_index_;
00114 };
00115 
00117 class TrajectoryExecutionMonitor
00118 {
00119 
00120 public:
00121   
00122   TrajectoryExecutionMonitor() : cm_("robot_description"){};
00123 
00125   void addTrajectoryRecorder(boost::shared_ptr<TrajectoryRecorder>& trajectory_recorder);
00126 
00128   void addTrajectoryControllerHandler(boost::shared_ptr<TrajectoryControllerHandler>& trajectory_controller_handler);
00129 
00132   void executeTrajectories(const std::vector<TrajectoryExecutionRequest>& to_execute,
00133                            const boost::function<bool(TrajectoryExecutionDataVector)>& done_callback);
00134 
00135 protected:
00136   
00137   bool sendTrajectory(const TrajectoryExecutionRequest& ter);
00138   
00140   void trajectoryFinishedCallbackFunction( TrajectoryControllerState controller_state );
00141 
00143   bool closeEnough(const TrajectoryExecutionRequest& ter,
00144                    const TrajectoryExecutionData& ted);
00145   
00147   void compareLastRecordedToStart(const TrajectoryExecutionRequest& last_ter,
00148                                   const TrajectoryExecutionRequest& next_ter,
00149                                   const TrajectoryExecutionData& ted);
00150 
00151 
00152   boost::function<bool(TrajectoryExecutionDataVector)> result_callback_;
00153   TrajectoryExecutionDataVector execution_result_vector_;
00154   const std::vector<TrajectoryExecutionRequest>* execution_data_;
00155   unsigned int current_trajectory_index_;
00156 
00157   boost::shared_ptr<TrajectoryControllerHandler> last_requested_handler_;
00158   std::map<std::string, boost::shared_ptr<TrajectoryRecorder> > trajectory_recorder_map_;
00159   std::map<std::string, boost::shared_ptr<TrajectoryControllerHandler> > trajectory_controller_handler_map_;
00160 
00161   planning_environment::CollisionModels cm_;
00162 
00163 };
00164 
00165 }


trajectory_execution_monitor
Author(s): Gil Jones
autogenerated on Fri Dec 6 2013 21:09:24