passive_joints_widget.cpp
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 // SA
00038 #include "passive_joints_widget.h"
00039 // Qt
00040 #include <QFormLayout>
00041 #include <QMessageBox>
00042 
00043 namespace moveit_setup_assistant
00044 {
00045 // ******************************************************************************************
00046 // Constructor
00047 // ******************************************************************************************
00048 PassiveJointsWidget::PassiveJointsWidget(QWidget* parent, moveit_setup_assistant::MoveItConfigDataPtr config_data)
00049   : SetupScreenWidget(parent), config_data_(config_data)
00050 {
00051   // Basic widget container
00052   QVBoxLayout* layout = new QVBoxLayout();
00053 
00054   // Top Header Area ------------------------------------------------
00055 
00056   HeaderWidget* header = new HeaderWidget("Passive Joints", "Specify the set of passive joints (not actuated). Joint "
00057                                                             "state is not expected to be published for these joints.",
00058                                           this);
00059   layout->addWidget(header);
00060 
00061   // Joints edit widget
00062   joints_widget_ = new DoubleListWidget(this, config_data_, "Joint Collection", "Joint", false);
00063   connect(joints_widget_, SIGNAL(selectionUpdated()), this, SLOT(selectionUpdated()));
00064   connect(joints_widget_, SIGNAL(previewSelected(std::vector<std::string>)), this,
00065           SLOT(previewSelectedJoints(std::vector<std::string>)));
00066 
00067   // Set the title
00068   joints_widget_->title_->setText("");
00069 
00070   joints_widget_->setColumnNames("Active Joints", "Passive Joints");
00071 
00072   layout->addWidget(joints_widget_);
00073 
00074   // Finish Layout --------------------------------------------------
00075   this->setLayout(layout);
00076 }
00077 
00078 // ******************************************************************************************
00079 //
00080 // ******************************************************************************************
00081 void PassiveJointsWidget::focusGiven()
00082 {
00083   joints_widget_->clearContents();
00084 
00085   // Retrieve pointer to the shared kinematic model
00086   const robot_model::RobotModelConstPtr& model = config_data_->getRobotModel();
00087 
00088   // Get the names of the all joints
00089   const std::vector<std::string>& joints = model->getJointModelNames();
00090 
00091   if (joints.size() == 0)
00092   {
00093     QMessageBox::critical(this, "Error Loading", "No joints found for robot model");
00094     return;
00095   }
00096   std::vector<std::string> active_joints;
00097   for (std::size_t i = 0; i < joints.size(); ++i)
00098     if (model->getJointModel(joints[i])->getVariableCount() > 0)
00099       active_joints.push_back(joints[i]);
00100 
00101   // Set the available joints (left box)
00102   joints_widget_->setAvailable(active_joints);
00103 
00104   std::vector<std::string> passive_joints;
00105   for (std::size_t i = 0; i < config_data_->srdf_->passive_joints_.size(); ++i)
00106     passive_joints.push_back(config_data_->srdf_->passive_joints_[i].name_);
00107   joints_widget_->setSelected(passive_joints);
00108 }
00109 
00110 // ******************************************************************************************
00111 //
00112 // ******************************************************************************************
00113 void PassiveJointsWidget::selectionUpdated()
00114 {
00115   config_data_->srdf_->passive_joints_.clear();
00116   for (int i = 0; i < joints_widget_->selected_data_table_->rowCount(); ++i)
00117   {
00118     srdf::Model::PassiveJoint pj;
00119     pj.name_ = joints_widget_->selected_data_table_->item(i, 0)->text().toStdString();
00120     config_data_->srdf_->passive_joints_.push_back(pj);
00121   }
00122   config_data_->changes |= MoveItConfigData::PASSIVE_JOINTS;
00123 }
00124 
00125 // ******************************************************************************************
00126 // Called from Double List widget to highlight joints
00127 // ******************************************************************************************
00128 void PassiveJointsWidget::previewSelectedJoints(std::vector<std::string> joints)
00129 {
00130   // Unhighlight all links
00131   Q_EMIT unhighlightAll();
00132 
00133   for (int i = 0; i < joints.size(); ++i)
00134   {
00135     const robot_model::JointModel* joint_model = config_data_->getRobotModel()->getJointModel(joints[i]);
00136 
00137     // Check that a joint model was found
00138     if (!joint_model)
00139     {
00140       continue;
00141     }
00142 
00143     // Get the name of the link
00144     const std::string link = joint_model->getChildLinkModel()->getName();
00145 
00146     if (link.empty())
00147     {
00148       continue;
00149     }
00150 
00151     // Highlight link
00152     Q_EMIT highlightLink(link, QColor(255, 0, 0));
00153   }
00154 }
00155 
00156 }  // namespace


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Mon Jul 24 2017 02:22:29