kinematic_chain_widget.h
Go to the documentation of this file.
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_KINEMATIC_CHAIN_WIDGET_
00038 #define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_KINEMATIC_CHAIN_WIDGET_
00039 
00040 #include <QWidget>
00041 #include <QLabel>
00042 #include <QTreeWidget>
00043 
00044 #ifndef Q_MOC_RUN
00045 #include <moveit/setup_assistant/tools/moveit_config_data.h>
00046 #include <ros/ros.h>
00047 #endif
00048 
00049 namespace moveit_setup_assistant
00050 {
00051 class KinematicChainWidget : public QWidget
00052 {
00053   Q_OBJECT
00054 
00055   // ******************************************************************************************
00056   // Reusable double list widget for selecting and deselecting a subset from a set
00057   // ******************************************************************************************
00058 public:
00059   // ******************************************************************************************
00060   // Public Functions
00061   // ******************************************************************************************
00062 
00064   KinematicChainWidget(QWidget* parent, moveit_setup_assistant::MoveItConfigDataPtr config_data);
00065 
00067   void setAvailable();
00068 
00070   void setSelected(const std::string& base_link, const std::string& tip_link);
00071 
00072   void addLinktoTreeRecursive(const robot_model::LinkModel* link, const robot_model::LinkModel* parent);
00073 
00074   bool addLinkChildRecursive(QTreeWidgetItem* parent, const robot_model::LinkModel* link,
00075                              const std::string& parent_name);
00076 
00077   // ******************************************************************************************
00078   // Qt Components
00079   // ******************************************************************************************
00080 
00081   QLabel* title_;  // specify the title from the parent widget
00082   QTreeWidget* link_tree_;
00083   QLineEdit* base_link_field_;
00084   QLineEdit* tip_link_field_;
00085 
00086 private Q_SLOTS:
00087 
00088   // ******************************************************************************************
00089   // Slot Event Functions
00090   // ******************************************************************************************
00091 
00093   void baseLinkTreeClick();
00094 
00096   void tipLinkTreeClick();
00097 
00099   void alterTree(const QString& link);
00100 
00102   void itemSelected();
00103 
00104 Q_SIGNALS:
00105 
00106   // ******************************************************************************************
00107   // Emitted Signals
00108   // ******************************************************************************************
00109 
00111   void doneEditing();
00112 
00114   void cancelEditing();
00115 
00117   void highlightLink(const std::string& name, const QColor&);
00118 
00120   void unhighlightAll();
00121 
00122 private:
00123   // ******************************************************************************************
00124   // Variables
00125   // ******************************************************************************************
00126 
00128   moveit_setup_assistant::MoveItConfigDataPtr config_data_;
00129 
00131   bool kinematic_chain_loaded_;
00132 
00133   // ******************************************************************************************
00134   // Private Functions
00135   // ******************************************************************************************
00136 };
00137 }
00138 
00139 #endif


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Wed Jun 19 2019 19:25:13