00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2012, 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 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 00035 /* Author: Dave Coleman */ 00036 00037 #ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_ROBOT_POSES_WIDGET_ 00038 #define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_ROBOT_POSES_WIDGET_ 00039 00040 // Qt 00041 #include <QWidget> 00042 #include <QVBoxLayout> 00043 #include <QHBoxLayout> 00044 #include <QScrollArea> 00045 #include <QGroupBox> 00046 #include <QLabel> 00047 #include <QPushButton> 00048 #include <QTableWidget> 00049 #include <QStackedLayout> 00050 #include <QString> 00051 #include <QComboBox> 00052 00053 // SA 00054 #ifndef Q_MOC_RUN 00055 #include <moveit/setup_assistant/tools/moveit_config_data.h> 00056 #include <moveit/planning_scene/planning_scene.h> // for collision stuff 00057 #include <ros/ros.h> 00058 #endif 00059 00060 #include "header_widget.h" 00061 #include "setup_screen_widget.h" // a base class for screens in the setup assistant 00062 00063 namespace moveit_setup_assistant 00064 { 00065 class RobotPosesWidget : public SetupScreenWidget 00066 { 00067 Q_OBJECT 00068 00069 public: 00070 // ****************************************************************************************** 00071 // Public Functions 00072 // ****************************************************************************************** 00073 00074 RobotPosesWidget(QWidget* parent, moveit_setup_assistant::MoveItConfigDataPtr config_data); 00075 00077 virtual void focusGiven(); 00078 00079 // ****************************************************************************************** 00080 // Qt Components 00081 // ****************************************************************************************** 00082 QTableWidget* data_table_; 00083 QPushButton* btn_edit_; 00084 QPushButton* btn_delete_; 00085 QPushButton* btn_save_; 00086 QPushButton* btn_cancel_; 00087 QStackedLayout* stacked_layout_; 00088 QScrollArea* scroll_area_; 00089 QVBoxLayout* column2_; 00090 QLineEdit* pose_name_field_; 00091 QComboBox* group_name_field_; 00092 QWidget* joint_list_widget_; 00093 QVBoxLayout* joint_list_layout_; 00094 QWidget* pose_list_widget_; 00095 QWidget* pose_edit_widget_; 00096 QLabel* collision_warning_; 00097 00098 private Q_SLOTS: 00099 00100 // ****************************************************************************************** 00101 // Slot Event Functions 00102 // ****************************************************************************************** 00103 00105 void showNewScreen(); 00106 00108 void editSelected(); 00109 00111 void editDoubleClicked(int row, int column); 00112 00114 void previewClicked(int row, int column); 00115 00117 void deleteSelected(); 00118 00120 void doneEditing(); 00121 00123 void cancelEditing(); 00124 00126 void loadJointSliders(const QString& selected); 00127 00129 void showDefaultPose(); 00130 00132 void playPoses(); 00133 00140 void updateRobotModel(const std::string& name, double value); 00141 00143 void publishJoints(); 00144 00145 private: 00146 // ****************************************************************************************** 00147 // Variables 00148 // ****************************************************************************************** 00149 00151 moveit_setup_assistant::MoveItConfigDataPtr config_data_; 00152 00154 std::string current_edit_pose_; 00155 00157 std::map<std::string, double> joint_state_map_; 00158 00160 std::vector<const robot_model::JointModel*> joint_models_; 00161 00163 ros::Publisher pub_robot_state_; 00164 00165 // ****************************************************************************************** 00166 // Collision Variables 00167 // ****************************************************************************************** 00168 collision_detection::CollisionRequest request; 00169 00170 // ****************************************************************************************** 00171 // Private Functions 00172 // ****************************************************************************************** 00173 00180 srdf::Model::GroupState* findPoseByName(const std::string& name); 00181 00187 QWidget* createContentsWidget(); 00188 00194 QWidget* createEditWidget(); 00195 00200 void loadDataTable(); 00201 00206 void loadGroupsComboBox(); 00207 00213 void edit(const std::string& name); 00214 00218 void showPose(srdf::Model::GroupState* pose); 00219 }; 00220 00221 // ****************************************************************************************** 00222 // ****************************************************************************************** 00223 // Slider Widget 00224 // ****************************************************************************************** 00225 // ****************************************************************************************** 00226 class SliderWidget : public QWidget 00227 { 00228 Q_OBJECT 00229 00230 public: 00231 // ****************************************************************************************** 00232 // Public Functions 00233 // ****************************************************************************************** 00234 00241 SliderWidget(QWidget* parent, const robot_model::JointModel* joint_model, double init_value); 00242 00246 ~SliderWidget(); 00247 00248 // ****************************************************************************************** 00249 // Qt Components 00250 // ****************************************************************************************** 00251 00252 QLabel* joint_label_; 00253 QSlider* joint_slider_; 00254 QLineEdit* joint_value_; 00255 00256 private Q_SLOTS: 00257 00258 // ****************************************************************************************** 00259 // Slot Event Functions 00260 // ****************************************************************************************** 00261 00263 void changeJointValue(int value); 00264 00266 void changeJointSlider(); 00267 00268 Q_SIGNALS: 00269 00270 // ****************************************************************************************** 00271 // Emitted Signal Functions 00272 // ****************************************************************************************** 00273 00275 void jointValueChanged(const std::string& name, double value); 00276 00277 private: 00278 // ****************************************************************************************** 00279 // Variables 00280 // ****************************************************************************************** 00281 00282 // Ptr to the joint's data 00283 const robot_model::JointModel* joint_model_; 00284 00285 // Max & min position 00286 double max_position_; 00287 double min_position_; 00288 00289 // ****************************************************************************************** 00290 // Private Functions 00291 // ****************************************************************************************** 00292 }; 00293 00294 } // namespace 00295 00296 // Declare std::string as metatype so we can use it in a signal 00297 Q_DECLARE_METATYPE(std::string) 00298 00299 #endif