$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2008, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Willow Garage nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 * \author E. Gil Jones 00036 *********************************************************************/ 00037 00038 #ifndef MOVE_ARM_WAREHOUSE_LOGGER_H_ 00039 #define MOVE_ARM_WAREHOUSE_LOGGER_H_ 00040 00041 #include <mongo_ros/message_collection.h> 00042 00043 #include <arm_navigation_msgs/PlanningScene.h> 00044 #include <arm_navigation_msgs/MotionPlanRequest.h> 00045 #include <arm_navigation_msgs/ArmNavigationErrorCodes.h> 00046 #include <trajectory_msgs/JointTrajectory.h> 00047 #include <head_monitor_msgs/HeadMonitorFeedback.h> 00048 00049 namespace move_arm_warehouse 00050 { 00051 00052 class MoveArmWarehouseLoggerReader { 00053 00054 public: 00055 00056 MoveArmWarehouseLoggerReader(); 00057 00058 ~MoveArmWarehouseLoggerReader(); 00059 00060 const std::string& getHostname() const { 00061 return hostname_; 00062 } 00063 00067 00068 void pushPlanningSceneToWarehouseWithoutId(const arm_navigation_msgs::PlanningScene& planning_scene, 00069 unsigned int& id); 00070 00071 void pushPlanningSceneToWarehouse(const arm_navigation_msgs::PlanningScene& planning_scene, 00072 const unsigned int ID); 00073 00074 void pushMotionPlanRequestToWarehouse(const unsigned int planning_id, 00075 const unsigned int mpr_id, 00076 const std::string& stage_name, 00077 const arm_navigation_msgs::MotionPlanRequest& motion_plan_request); 00078 00079 void pushJointTrajectoryToWarehouse(const unsigned int id, 00080 const std::string& trajectory_source, 00081 const ros::Duration& production_time, 00082 const trajectory_msgs::JointTrajectory& trajectory, 00083 const unsigned int ID, 00084 const unsigned int motion_plan_ID, 00085 const arm_navigation_msgs::ArmNavigationErrorCodes& error_code); 00086 00087 void pushOutcomeToWarehouse(const unsigned int id, 00088 const std::string& pipeline_stage, 00089 const arm_navigation_msgs::ArmNavigationErrorCodes& error_codes); 00090 00091 void pushPausedStateToWarehouse(const unsigned int id, 00092 const head_monitor_msgs::HeadMonitorFeedback& feedback); 00093 00097 00098 void getAvailablePlanningSceneList(const std::string& hostname, 00099 std::vector<unsigned int>& planning_scene_ids_, 00100 std::vector<ros::Time>& creation_times); 00101 00102 bool getPlanningScene(const std::string& hostname, 00103 const unsigned int& id, 00104 arm_navigation_msgs::PlanningScene& planning_scene, 00105 std::string& hostname_out); 00106 00107 bool getAssociatedOutcomes(const std::string& hostname, 00108 const unsigned int planning_scene_id, 00109 std::vector<std::string>& pipeline_names, 00110 std::vector<arm_navigation_msgs::ArmNavigationErrorCodes>& error_codes); 00111 00112 bool getAssociatedMotionPlanRequestsStageNames(const std::string& hostname, 00113 const unsigned int id, 00114 std::vector<std::string>& stage_names); 00115 00116 bool getAssociatedMotionPlanRequest(const std::string& hostname, 00117 const unsigned int planning_scene_id, 00118 const unsigned int motion_plan_id, 00119 arm_navigation_msgs::MotionPlanRequest& request); 00120 00121 bool getAssociatedMotionPlanRequests(const std::string& hostname, 00122 const unsigned int planning_scene_id, 00123 std::vector<unsigned int>& IDs, 00124 std::vector<std::string>& stage_names, 00125 std::vector<arm_navigation_msgs::MotionPlanRequest>& requests); 00126 00127 bool getAssociatedJointTrajectorySources(const std::string& hostname, 00128 const unsigned int planning_scene_id, 00129 const unsigned int motion_request_id, 00130 std::vector<unsigned int>& ids, 00131 std::vector<std::string>& trajectory_sources); 00132 00133 bool getAssociatedJointTrajectory(const std::string& hostname, 00134 const unsigned int planning_scene_id, 00135 const unsigned int motion_plan_id, 00136 const unsigned int trajectory_id, 00137 ros::Duration& processing_time, 00138 trajectory_msgs::JointTrajectory& joint_trajectory); 00139 00140 bool getAssociatedJointTrajectories(const std::string& hostname, 00141 const unsigned int planning_scene_id, 00142 const unsigned int motion_plan_id, 00143 std::vector<trajectory_msgs::JointTrajectory>& trajectories, 00144 std::vector<std::string>& sources, 00145 std::vector<unsigned int>& IDs, 00146 std::vector<ros::Duration>& durations, 00147 std::vector<int32_t>& error_codes); 00148 00149 bool getAssociatedPausedStates(const std::string& hostname, 00150 const unsigned int planning_scene_id, 00151 std::vector<ros::Time>& paused_times); 00152 00153 bool getAssociatedPausedState(const std::string& hostname, 00154 const unsigned int planning_scene_id, 00155 const ros::Time& paused_time, 00156 head_monitor_msgs::HeadMonitorFeedback& paused_state); 00157 00158 bool hasPlanningScene(const std::string& hostname, 00159 const unsigned int id); 00160 00161 bool removePlanningSceneAndAssociatedDataFromWarehouse(const std::string& hostname, 00162 const unsigned int id); 00163 00164 unsigned int determineNextPlanningSceneId(); 00165 00166 protected: 00167 00168 mongo_ros::Metadata initializeMetadataWithHostname(); 00169 00170 void addPlanningSceneTimeToMetadata(const arm_navigation_msgs::PlanningScene& planning_scene, mongo_ros::Metadata& metadata); 00171 void addPlanningSceneIdToMetadata(const unsigned int& id, 00172 mongo_ros::Metadata& metadata); 00173 00174 00175 mongo_ros::Query makeQueryForPlanningSceneTime(const ros::Time& time); 00176 mongo_ros::Query makeQueryForPlanningSceneId(const unsigned int id); 00177 00178 mongo_ros::MessageCollection<arm_navigation_msgs::PlanningScene>* planning_scene_collection_; 00179 mongo_ros::MessageCollection<arm_navigation_msgs::MotionPlanRequest>* motion_plan_request_collection_; 00180 mongo_ros::MessageCollection<trajectory_msgs::JointTrajectory>* trajectory_collection_; 00181 mongo_ros::MessageCollection<arm_navigation_msgs::ArmNavigationErrorCodes>* outcome_collection_; 00182 mongo_ros::MessageCollection<head_monitor_msgs::HeadMonitorFeedback>* paused_state_collection_; 00183 00184 std::string hostname_; 00185 00186 }; 00187 00188 } 00189 #endif