| Line |
Branch |
Exec |
Source |
| 1 |
|
|
// |
| 2 |
|
|
// Copyright (c) CNRS |
| 3 |
|
|
// Authors: Joseph Mirabel and Heidy Dallard |
| 4 |
|
|
// |
| 5 |
|
|
|
| 6 |
|
|
#include "hppmanipulationwidgetsplugin/hppmanipulationwidgetsplugin.hh" |
| 7 |
|
|
|
| 8 |
|
|
#include <assert.h> |
| 9 |
|
|
|
| 10 |
|
|
#include <QAction> |
| 11 |
|
|
#include <QDockWidget> |
| 12 |
|
|
#include <QLayout> |
| 13 |
|
|
#include <QListWidgetItem> |
| 14 |
|
|
#include <QPushButton> |
| 15 |
|
|
#include <QVBoxLayout> |
| 16 |
|
|
#include <sstream> |
| 17 |
|
|
|
| 18 |
|
|
#include "gepetto/gui/mainwindow.hh" |
| 19 |
|
|
#include "gepetto/gui/windows-manager.hh" |
| 20 |
|
|
#include "hppmanipulationwidgetsplugin/linkwidget.hh" |
| 21 |
|
|
#include "hppmanipulationwidgetsplugin/roadmap.hh" |
| 22 |
|
|
#include "hppwidgetsplugin/conversions.hh" |
| 23 |
|
|
#include "hppwidgetsplugin/jointtreewidget.hh" |
| 24 |
|
|
|
| 25 |
|
|
using CORBA::ULong; |
| 26 |
|
|
|
| 27 |
|
|
namespace gv = gepetto::viewer; |
| 28 |
|
|
|
| 29 |
|
|
namespace hpp { |
| 30 |
|
|
namespace gui { |
| 31 |
|
✗ |
HppManipulationWidgetsPlugin::HppManipulationWidgetsPlugin() |
| 32 |
|
|
: HppWidgetsPlugin(), |
| 33 |
|
✗ |
hpp_(NULL), |
| 34 |
|
✗ |
toolBar_(NULL), |
| 35 |
|
✗ |
tw_(NULL), |
| 36 |
|
✗ |
graphBuilder_(NULL) {} |
| 37 |
|
|
|
| 38 |
|
✗ |
HppManipulationWidgetsPlugin::~HppManipulationWidgetsPlugin() { |
| 39 |
|
✗ |
if (graphBuilder_) { |
| 40 |
|
✗ |
delete graphBuilder_; |
| 41 |
|
✗ |
graphBuilder_ = NULL; |
| 42 |
|
|
} |
| 43 |
|
|
} |
| 44 |
|
|
|
| 45 |
|
✗ |
void HppManipulationWidgetsPlugin::init() { |
| 46 |
|
✗ |
HppWidgetsPlugin::init(); |
| 47 |
|
✗ |
gepetto::gui::MainWindow* main = gepetto::gui::MainWindow::instance(); |
| 48 |
|
|
|
| 49 |
|
✗ |
toolBar_ = |
| 50 |
|
✗ |
gepetto::gui::MainWindow::instance()->addToolBar("Manipulation tools"); |
| 51 |
|
✗ |
toolBar_->setObjectName("hppmanipulationwidgetsplugin.manipulationtools"); |
| 52 |
|
✗ |
QAction* drawRContact = new QAction("Draw robot contacts", toolBar_); |
| 53 |
|
✗ |
QAction* drawEContact = new QAction("Draw environment contacts", toolBar_); |
| 54 |
|
✗ |
toolBar_->addAction(drawRContact); |
| 55 |
|
✗ |
toolBar_->addAction(drawEContact); |
| 56 |
|
✗ |
connect(drawRContact, SIGNAL(triggered()), SLOT(drawRobotContacts())); |
| 57 |
|
✗ |
connect(drawEContact, SIGNAL(triggered()), SLOT(drawEnvironmentContacts())); |
| 58 |
|
✗ |
QAction* drawHFrame = new QAction("Draw handles frame", toolBar_); |
| 59 |
|
✗ |
QAction* drawGFrame = new QAction("Draw grippers frame", toolBar_); |
| 60 |
|
✗ |
toolBar_->addAction(drawHFrame); |
| 61 |
|
✗ |
toolBar_->addAction(drawGFrame); |
| 62 |
|
✗ |
connect(drawHFrame, SIGNAL(triggered()), SLOT(drawHandlesFrame())); |
| 63 |
|
✗ |
connect(drawGFrame, SIGNAL(triggered()), SLOT(drawGrippersFrame())); |
| 64 |
|
✗ |
QAction* autoBuildGraph = new QAction("Autobuild constraint graph", toolBar_); |
| 65 |
|
✗ |
toolBar_->addAction(autoBuildGraph); |
| 66 |
|
✗ |
connect(autoBuildGraph, SIGNAL(triggered()), SLOT(autoBuildGraph())); |
| 67 |
|
|
|
| 68 |
|
✗ |
main->registerSlot("autoBuildGraph", this); |
| 69 |
|
✗ |
main->registerSlot("drawRobotContacts", this); |
| 70 |
|
✗ |
main->registerSlot("drawEnvironmentsContacts", this); |
| 71 |
|
|
} |
| 72 |
|
|
|
| 73 |
|
✗ |
QString HppManipulationWidgetsPlugin::name() const { |
| 74 |
|
✗ |
return QString("Widgets for hpp-manipulation-corba"); |
| 75 |
|
|
} |
| 76 |
|
|
|
| 77 |
|
✗ |
void HppManipulationWidgetsPlugin::loadRobotModel( |
| 78 |
|
|
gepetto::gui::DialogLoadRobot::RobotDefinition rd) { |
| 79 |
|
✗ |
if (!hpp_) return; |
| 80 |
|
|
try { |
| 81 |
|
✗ |
hpp::floatSeq_var q = client()->robot()->getCurrentConfig(); |
| 82 |
|
|
(void)q; |
| 83 |
|
✗ |
} catch (hpp::Error const& e) { |
| 84 |
|
✗ |
client()->robot()->createRobot(to_corba("composite").in()); |
| 85 |
|
|
} |
| 86 |
|
✗ |
QString urdfFilename("package://" + rd.package_ + "/urdf/" + rd.modelName_ + |
| 87 |
|
✗ |
rd.urdfSuf_ + ".urdf"); |
| 88 |
|
✗ |
QString srdfFilename("package://" + rd.package_ + "/srdf/" + rd.modelName_ + |
| 89 |
|
✗ |
rd.srdfSuf_ + ".srdf"); |
| 90 |
|
✗ |
hpp_->robot()->insertRobotModel( |
| 91 |
|
✗ |
to_corba(rd.robotName_).in(), to_corba(rd.rootJointType_).in(), |
| 92 |
|
✗ |
to_corba(urdfFilename).in(), to_corba(srdfFilename).in()); |
| 93 |
|
|
// This is already done in requestRefresh |
| 94 |
|
|
// jointTreeWidget_->reload(); |
| 95 |
|
✗ |
gepetto::gui::MainWindow::instance()->requestRefresh(); |
| 96 |
|
✗ |
gepetto::gui::MainWindow::instance()->requestApplyCurrentConfiguration(); |
| 97 |
|
✗ |
emit logSuccess("Robot " + rd.name_ + " loaded"); |
| 98 |
|
|
} |
| 99 |
|
|
|
| 100 |
|
✗ |
void HppManipulationWidgetsPlugin::loadEnvironmentModel( |
| 101 |
|
|
gepetto::gui::DialogLoadEnvironment::EnvironmentDefinition ed) { |
| 102 |
|
✗ |
if (!hpp_) return; |
| 103 |
|
|
try { |
| 104 |
|
✗ |
hpp::floatSeq_var q = client()->robot()->getCurrentConfig(); |
| 105 |
|
|
(void)q; |
| 106 |
|
✗ |
} catch (hpp::Error const& e) { |
| 107 |
|
✗ |
client()->robot()->createRobot(to_corba("composite").in()); |
| 108 |
|
|
} |
| 109 |
|
✗ |
QString urdfFilename("package://" + ed.package_ + "/urdf/" + |
| 110 |
|
✗ |
ed.urdfFilename_ + ed.urdfSuf_ + ".urdf"); |
| 111 |
|
✗ |
QString srdfFilename("package://" + ed.package_ + "/srdf/" + |
| 112 |
|
✗ |
ed.urdfFilename_ + ed.srdfSuf_ + ".srdf"); |
| 113 |
|
✗ |
hpp_->robot()->loadEnvironmentModel(to_corba(urdfFilename).in(), |
| 114 |
|
✗ |
to_corba(srdfFilename).in(), |
| 115 |
|
✗ |
to_corba(ed.name_ + "/").in()); |
| 116 |
|
✗ |
HppWidgetsPlugin::computeObjectPosition(); |
| 117 |
|
✗ |
gepetto::gui::MainWindow::instance()->requestRefresh(); |
| 118 |
|
✗ |
emit logSuccess("Environment " + ed.name_ + " loaded"); |
| 119 |
|
|
} |
| 120 |
|
|
|
| 121 |
|
✗ |
std::string HppManipulationWidgetsPlugin::getBodyFromJoint( |
| 122 |
|
|
const std::string& jointName) const { |
| 123 |
|
|
/// TODO: fix this |
| 124 |
|
✗ |
return HppWidgetsPlugin::getBodyFromJoint(jointName); |
| 125 |
|
|
} |
| 126 |
|
|
|
| 127 |
|
✗ |
void HppManipulationWidgetsPlugin::openConnection() { |
| 128 |
|
✗ |
HppWidgetsPlugin::openConnection(); |
| 129 |
|
✗ |
hpp_ = new HppManipClient(0, 0); |
| 130 |
|
✗ |
QByteArray iiop = getHppIIOPurl().toLatin1(); |
| 131 |
|
✗ |
QByteArray context = getHppContext().toLatin1(); |
| 132 |
|
|
try { |
| 133 |
|
✗ |
hpp_->connect(iiop.constData(), context.constData()); |
| 134 |
|
|
hpp::Names_t_var for_memory_deletion = |
| 135 |
|
✗ |
hpp_->problem()->getAvailable("type"); |
| 136 |
|
✗ |
} catch (const CORBA::Exception& e) { |
| 137 |
|
✗ |
QString error("Could not find the manipulation server. Is it running ?"); |
| 138 |
|
✗ |
error += "\n"; |
| 139 |
|
✗ |
error += e._name(); |
| 140 |
|
✗ |
error += " : "; |
| 141 |
|
✗ |
error += e._rep_id(); |
| 142 |
|
✗ |
gepetto::gui::MainWindow* main = gepetto::gui::MainWindow::instance(); |
| 143 |
|
✗ |
if (main != NULL) |
| 144 |
|
✗ |
main->logError(error); |
| 145 |
|
|
else |
| 146 |
|
✗ |
qDebug() << error; |
| 147 |
|
|
|
| 148 |
|
✗ |
if (hpp_) delete hpp_; |
| 149 |
|
✗ |
hpp_ = NULL; |
| 150 |
|
|
} |
| 151 |
|
|
} |
| 152 |
|
|
|
| 153 |
|
✗ |
void HppManipulationWidgetsPlugin::closeConnection() { |
| 154 |
|
✗ |
HppWidgetsPlugin::closeConnection(); |
| 155 |
|
✗ |
if (hpp_) delete hpp_; |
| 156 |
|
✗ |
hpp_ = NULL; |
| 157 |
|
|
} |
| 158 |
|
|
|
| 159 |
|
|
HppManipulationWidgetsPlugin::HppManipClient* |
| 160 |
|
✗ |
HppManipulationWidgetsPlugin::manipClient() const { |
| 161 |
|
✗ |
return hpp_; |
| 162 |
|
|
} |
| 163 |
|
|
|
| 164 |
|
✗ |
Roadmap* HppManipulationWidgetsPlugin::createRoadmap( |
| 165 |
|
|
const std::string& jointName) { |
| 166 |
|
✗ |
ManipulationRoadmap* r = new ManipulationRoadmap(this); |
| 167 |
|
✗ |
r->initRoadmapFromJoint(jointName); |
| 168 |
|
✗ |
return r; |
| 169 |
|
|
} |
| 170 |
|
|
|
| 171 |
|
✗ |
void HppManipulationWidgetsPlugin::drawContactSurface( |
| 172 |
|
|
const std::string& name, hpp::intSeq_var& indexes, |
| 173 |
|
|
hpp::floatSeqSeq_var& points, CORBA::ULong j, float epsilon) { |
| 174 |
|
✗ |
gepetto::gui::MainWindow* main = gepetto::gui::MainWindow::instance(); |
| 175 |
|
✗ |
osgVector4 color(0, 1, 0, 1); |
| 176 |
|
✗ |
osgVector3 norm(0, 0, 0); |
| 177 |
|
✗ |
CORBA::Long iPts = (j == 0) ? 0 : indexes[j - 1]; |
| 178 |
|
✗ |
gv::WindowsManager::Vec3ArrayPtr_t ps(new osg::Vec3Array); |
| 179 |
|
✗ |
ps->resize(indexes[j] - iPts); |
| 180 |
|
✗ |
if (ps->size() > 3) { |
| 181 |
|
✗ |
osgVector3 a((float)(points[iPts][0] - points[iPts + 1][0]), |
| 182 |
|
✗ |
(float)(points[iPts][1] - points[iPts + 1][1]), |
| 183 |
|
✗ |
(float)(points[iPts][2] - points[iPts + 1][2])); |
| 184 |
|
✗ |
osgVector3 b((float)(points[iPts + 1][0] - points[iPts + 2][0]), |
| 185 |
|
✗ |
(float)(points[iPts + 1][1] - points[iPts + 2][1]), |
| 186 |
|
✗ |
(float)(points[iPts + 1][2] - points[iPts + 2][2])); |
| 187 |
|
✗ |
osgVector3 c = a ^ b; |
| 188 |
|
✗ |
if (c.length() > 0.00001) norm = c / c.length(); |
| 189 |
|
|
} |
| 190 |
|
✗ |
for (CORBA::Long k = iPts; k < indexes[j]; ++k) { |
| 191 |
|
✗ |
(*ps)[k - iPts] = osgVector3((float)points[k][0], (float)points[k][1], |
| 192 |
|
✗ |
(float)points[k][2]) + |
| 193 |
|
✗ |
norm * epsilon; |
| 194 |
|
|
} |
| 195 |
|
✗ |
main->osg()->addCurve(name, ps, color); |
| 196 |
|
✗ |
main->osg()->setCurveMode(name, GL_POLYGON); |
| 197 |
|
|
} |
| 198 |
|
|
|
| 199 |
|
✗ |
void HppManipulationWidgetsPlugin::drawRobotContacts() { |
| 200 |
|
✗ |
if (!hpp_) return; |
| 201 |
|
✗ |
hpp::Names_t_var rcs = hpp_->problem()->getRobotContactNames(); |
| 202 |
|
✗ |
hpp::floatSeqSeq_var points; |
| 203 |
|
✗ |
hpp::intSeq_var indexes; |
| 204 |
|
✗ |
for (CORBA::ULong i = 0; i < rcs->length(); ++i) { |
| 205 |
|
|
hpp::Names_t_var cjs = |
| 206 |
|
✗ |
hpp_->problem()->getRobotContact(rcs[i], indexes.out(), points.out()); |
| 207 |
|
✗ |
for (CORBA::ULong j = 0; j < cjs->length(); ++j) { |
| 208 |
|
|
/// Create group |
| 209 |
|
✗ |
std::string target = createJointGroup(std::string(cjs[j])); |
| 210 |
|
|
|
| 211 |
|
|
/// Add the contacts |
| 212 |
|
✗ |
std::stringstream ssname; |
| 213 |
|
✗ |
ssname << target << "/contact_" << escapeJointName(std::string(rcs[i])) |
| 214 |
|
✗ |
<< "_" << j << "_"; |
| 215 |
|
✗ |
std::string name = ssname.str(); |
| 216 |
|
✗ |
drawContactSurface(name, indexes, points, j); |
| 217 |
|
|
} |
| 218 |
|
|
} |
| 219 |
|
✗ |
gepetto::gui::MainWindow::instance()->requestRefresh(); |
| 220 |
|
|
} |
| 221 |
|
|
|
| 222 |
|
✗ |
void HppManipulationWidgetsPlugin::drawEnvironmentContacts() { |
| 223 |
|
✗ |
if (!hpp_) return; |
| 224 |
|
✗ |
hpp::Names_t_var rcs = hpp_->problem()->getEnvironmentContactNames(); |
| 225 |
|
✗ |
hpp::floatSeqSeq_var points; |
| 226 |
|
✗ |
hpp::intSeq_var indexes; |
| 227 |
|
✗ |
for (CORBA::ULong i = 0; i < rcs->length(); ++i) { |
| 228 |
|
✗ |
hpp::Names_t_var cjs = hpp_->problem()->getEnvironmentContact( |
| 229 |
|
✗ |
rcs[i], indexes.out(), points.out()); |
| 230 |
|
✗ |
for (CORBA::ULong j = 0; j < cjs->length(); ++j) { |
| 231 |
|
|
/// Add the contacts |
| 232 |
|
✗ |
std::stringstream ssname; |
| 233 |
|
✗ |
ssname << "hpp-gui/contact_" << escapeJointName(std::string(rcs[i])) |
| 234 |
|
✗ |
<< "_" << j << "_"; |
| 235 |
|
✗ |
std::string name = ssname.str(); |
| 236 |
|
✗ |
drawContactSurface(name, indexes, points, j); |
| 237 |
|
|
} |
| 238 |
|
|
} |
| 239 |
|
✗ |
gepetto::gui::MainWindow::instance()->requestRefresh(); |
| 240 |
|
|
} |
| 241 |
|
|
|
| 242 |
|
✗ |
void HppManipulationWidgetsPlugin::drawHandlesFrame() { |
| 243 |
|
✗ |
if (!hpp_) return; |
| 244 |
|
✗ |
gepetto::gui::MainWindow* main = gepetto::gui::MainWindow::instance(); |
| 245 |
|
✗ |
hpp::Names_t_var rcs = hpp_->problem()->getAvailable("handle"); |
| 246 |
|
✗ |
hpp::Transform__var t(new Transform_); |
| 247 |
|
✗ |
gv::Configuration config; |
| 248 |
|
✗ |
const gv::WindowsManager::Color_t color(0, 1, 0, 1); |
| 249 |
|
✗ |
for (CORBA::ULong i = 0; i < rcs->length(); ++i) { |
| 250 |
|
|
const std::string jn = |
| 251 |
|
✗ |
hpp_->robot()->getHandlePositionInJoint(rcs[i], t.out()); |
| 252 |
|
✗ |
std::string groupName = createJointGroup(jn); |
| 253 |
|
✗ |
std::string hn = "handle_" + escapeJointName(std::string(rcs[i])); |
| 254 |
|
✗ |
fromHPP(t, config); |
| 255 |
|
✗ |
main->osg()->addXYZaxis(hn, color, 0.005f, 0.015f); |
| 256 |
|
✗ |
main->osg()->applyConfiguration(hn, config); |
| 257 |
|
✗ |
main->osg()->addToGroup(hn, groupName); |
| 258 |
|
|
} |
| 259 |
|
✗ |
main->osg()->refresh(); |
| 260 |
|
✗ |
gepetto::gui::MainWindow::instance()->requestRefresh(); |
| 261 |
|
|
} |
| 262 |
|
|
|
| 263 |
|
✗ |
void HppManipulationWidgetsPlugin::drawGrippersFrame() { |
| 264 |
|
✗ |
if (!hpp_) return; |
| 265 |
|
✗ |
gepetto::gui::MainWindow* main = gepetto::gui::MainWindow::instance(); |
| 266 |
|
✗ |
hpp::Names_t_var rcs = hpp_->problem()->getAvailable("gripper"); |
| 267 |
|
✗ |
hpp::Transform__var t(new Transform_); |
| 268 |
|
✗ |
gv::Configuration config; |
| 269 |
|
✗ |
const gv::WindowsManager::Color_t color(0, 1, 0, 1); |
| 270 |
|
✗ |
for (CORBA::ULong i = 0; i < rcs->length(); ++i) { |
| 271 |
|
|
const std::string jn = |
| 272 |
|
✗ |
hpp_->robot()->getGripperPositionInJoint(rcs[i], t.out()); |
| 273 |
|
✗ |
std::string groupName = createJointGroup(jn); |
| 274 |
|
✗ |
std::string hn = "gripper_" + escapeJointName(std::string(rcs[i])); |
| 275 |
|
✗ |
fromHPP(t, config); |
| 276 |
|
✗ |
main->osg()->addXYZaxis(hn, color, 0.005f, 0.015f); |
| 277 |
|
✗ |
main->osg()->applyConfiguration(hn, config); |
| 278 |
|
✗ |
main->osg()->addToGroup(hn, groupName); |
| 279 |
|
|
} |
| 280 |
|
✗ |
main->osg()->refresh(); |
| 281 |
|
✗ |
gepetto::gui::MainWindow::instance()->requestRefresh(); |
| 282 |
|
|
} |
| 283 |
|
|
|
| 284 |
|
|
HppManipulationWidgetsPlugin::NamesPair |
| 285 |
|
✗ |
HppManipulationWidgetsPlugin::convertMap( |
| 286 |
|
|
std::map<std::string, std::list<std::string> >& mapNames) { |
| 287 |
|
✗ |
HppManipulationWidgetsPlugin::NamesPair names; |
| 288 |
|
✗ |
int i = 0; |
| 289 |
|
|
int j; |
| 290 |
|
|
|
| 291 |
|
✗ |
names.first.length((CORBA::ULong)mapNames.size()); |
| 292 |
|
✗ |
names.second.length((CORBA::ULong)mapNames.size()); |
| 293 |
|
✗ |
for (HppManipulationWidgetsPlugin::MapNames::iterator itMap = |
| 294 |
|
✗ |
mapNames.begin(); |
| 295 |
|
✗ |
itMap != mapNames.end(); itMap++, i++) { |
| 296 |
|
✗ |
names.first[i] = (*itMap).first.c_str(); |
| 297 |
|
✗ |
names.second[i].length((CORBA::ULong)(*itMap).second.size()); |
| 298 |
|
✗ |
j = 0; |
| 299 |
|
✗ |
for (std::list<std::string>::iterator itList = (*itMap).second.begin(); |
| 300 |
|
✗ |
itList != (*itMap).second.end(); itList++, j++) { |
| 301 |
|
✗ |
names.second[i][j] = (*itList).c_str(); |
| 302 |
|
|
} |
| 303 |
|
|
} |
| 304 |
|
✗ |
return names; |
| 305 |
|
|
} |
| 306 |
|
|
|
| 307 |
|
✗ |
hpp::Names_t_var HppManipulationWidgetsPlugin::convertToNames( |
| 308 |
|
|
const QList<QListWidgetItem*>& l) { |
| 309 |
|
✗ |
hpp::Names_t_var cl = new hpp::Names_t; |
| 310 |
|
✗ |
cl->length(l.count()); |
| 311 |
|
✗ |
for (int i = 0; i < l.count(); i++) { |
| 312 |
|
✗ |
cl[i] = l[i]->text().toStdString().c_str(); |
| 313 |
|
|
} |
| 314 |
|
✗ |
return cl; |
| 315 |
|
|
} |
| 316 |
|
|
|
| 317 |
|
✗ |
void HppManipulationWidgetsPlugin::mergeShapes(MapNames& handles, |
| 318 |
|
|
MapNames& shapes) { |
| 319 |
|
✗ |
MapNames::iterator itH = handles.begin(); |
| 320 |
|
✗ |
MapNames::iterator itS = shapes.begin(); |
| 321 |
|
✗ |
while (itH != handles.end()) { |
| 322 |
|
✗ |
if (itS == shapes.end() || (*itH).first != (*itS).first) { |
| 323 |
|
✗ |
itS = shapes.insert( |
| 324 |
|
✗ |
itS, std::make_pair((*itH).first, std::list<std::string>())); |
| 325 |
|
|
} else |
| 326 |
|
✗ |
++itS; |
| 327 |
|
✗ |
itH++; |
| 328 |
|
|
} |
| 329 |
|
✗ |
while (itS != shapes.end()) { |
| 330 |
|
✗ |
handles.insert(handles.end(), |
| 331 |
|
✗ |
std::make_pair((*itS).first, std::list<std::string>())); |
| 332 |
|
✗ |
itS++; |
| 333 |
|
|
} |
| 334 |
|
|
} |
| 335 |
|
|
|
| 336 |
|
|
HppManipulationWidgetsPlugin::MapNames |
| 337 |
|
✗ |
HppManipulationWidgetsPlugin::getObjects() { |
| 338 |
|
✗ |
assert(hpp_ != NULL); |
| 339 |
|
✗ |
HppManipulationWidgetsPlugin::MapNames map; |
| 340 |
|
✗ |
hpp::Names_t_var handles = manipClient()->problem()->getAvailable("handle"); |
| 341 |
|
|
hpp::Names_t_var surfaces = |
| 342 |
|
✗ |
manipClient()->problem()->getAvailable("robotcontact"); |
| 343 |
|
|
|
| 344 |
|
✗ |
for (unsigned i = 0; i < handles->length(); ++i) { |
| 345 |
|
✗ |
std::string name(handles[i].in()); |
| 346 |
|
✗ |
size_t pos = name.find_first_of("/"); |
| 347 |
|
✗ |
std::string object = name.substr(0, pos); |
| 348 |
|
|
|
| 349 |
|
✗ |
if (map.find(object) == map.end()) { |
| 350 |
|
✗ |
map[object] = std::list<std::string>(); |
| 351 |
|
|
} |
| 352 |
|
|
} |
| 353 |
|
✗ |
for (unsigned i = 0; i < surfaces->length(); ++i) { |
| 354 |
|
✗ |
std::string name(surfaces[i].in()); |
| 355 |
|
✗ |
size_t pos = name.find_first_of("/"); |
| 356 |
|
✗ |
std::string object = name.substr(0, pos); |
| 357 |
|
|
|
| 358 |
|
✗ |
if (map.find(object) == map.end()) { |
| 359 |
|
✗ |
map[object] = std::list<std::string>(); |
| 360 |
|
|
} |
| 361 |
|
|
} |
| 362 |
|
✗ |
return map; |
| 363 |
|
|
} |
| 364 |
|
|
|
| 365 |
|
✗ |
void HppManipulationWidgetsPlugin::fillMap( |
| 366 |
|
|
HppManipulationWidgetsPlugin::MapNames& map, |
| 367 |
|
|
const QList<QListWidgetItem*>& list) { |
| 368 |
|
✗ |
for (int i = 0; i < list.count(); i++) { |
| 369 |
|
✗ |
std::string name(list[i]->text().toStdString()); |
| 370 |
|
✗ |
size_t pos = name.find_first_of("/"); |
| 371 |
|
✗ |
std::string object = name.substr(0, pos); |
| 372 |
|
|
|
| 373 |
|
✗ |
if (map.find(object) != map.end()) { |
| 374 |
|
✗ |
map[object].push_back(name); |
| 375 |
|
|
} |
| 376 |
|
|
} |
| 377 |
|
|
} |
| 378 |
|
|
|
| 379 |
|
✗ |
void print(const hpp::Names_t& v) { |
| 380 |
|
✗ |
std::cout << "[ "; |
| 381 |
|
✗ |
for (std::size_t i = 0; i < v.length(); i++) |
| 382 |
|
✗ |
std::cout << '"' << v[(CORBA::ULong)i] << "\", "; |
| 383 |
|
✗ |
std::cout << "]"; |
| 384 |
|
|
} |
| 385 |
|
✗ |
void print(const hpp::corbaserver::manipulation::Namess_t& v) { |
| 386 |
|
✗ |
std::cout << "[ "; |
| 387 |
|
✗ |
for (std::size_t i = 0; (std::size_t)i < v.length(); i++) { |
| 388 |
|
✗ |
print(v[(CORBA::ULong)i]); |
| 389 |
|
✗ |
std::cout << ", "; |
| 390 |
|
|
} |
| 391 |
|
✗ |
std::cout << "]"; |
| 392 |
|
|
} |
| 393 |
|
✗ |
void print(const hpp::corbaserver::manipulation::Rule& v) { |
| 394 |
|
✗ |
std::cout << "Rule("; |
| 395 |
|
✗ |
print(v.grippers); |
| 396 |
|
✗ |
std::cout << ", "; |
| 397 |
|
✗ |
print(v.handles); |
| 398 |
|
✗ |
std::cout << ", " << (v.link ? "True" : "False") << ')'; |
| 399 |
|
|
} |
| 400 |
|
✗ |
void print(const hpp::corbaserver::manipulation::Rules& v) { |
| 401 |
|
✗ |
std::cout << "[ "; |
| 402 |
|
✗ |
for (std::size_t i = 0; i < v.length(); i++) { |
| 403 |
|
✗ |
print(v[(CORBA::ULong)i]); |
| 404 |
|
✗ |
std::cout << ", "; |
| 405 |
|
|
} |
| 406 |
|
✗ |
std::cout << "]"; |
| 407 |
|
|
} |
| 408 |
|
|
|
| 409 |
|
✗ |
void HppManipulationWidgetsPlugin::buildGraph() { |
| 410 |
|
✗ |
if (!hpp_) return; |
| 411 |
|
✗ |
QListWidget* l = dynamic_cast<QListWidget*>(tw_->widget(0)); |
| 412 |
|
✗ |
HppManipulationWidgetsPlugin::MapNames handlesMap = getObjects(); |
| 413 |
|
✗ |
HppManipulationWidgetsPlugin::MapNames shapesMap = getObjects(); |
| 414 |
|
✗ |
hpp::Names_t_var grippers = convertToNames(l->selectedItems()); |
| 415 |
|
✗ |
l = dynamic_cast<QListWidget*>(tw_->widget(1)->layout()->itemAt(1)->widget()); |
| 416 |
|
✗ |
fillMap(handlesMap, l->selectedItems()); |
| 417 |
|
✗ |
l = dynamic_cast<QListWidget*>(tw_->widget(2)); |
| 418 |
|
✗ |
fillMap(shapesMap, l->selectedItems()); |
| 419 |
|
✗ |
l = dynamic_cast<QListWidget*>(tw_->widget(3)); |
| 420 |
|
✗ |
hpp::Names_t_var envNames = convertToNames(l->selectedItems()); |
| 421 |
|
|
hpp::corbaserver::manipulation::Rules_var rules = |
| 422 |
|
✗ |
dynamic_cast<LinkWidget*>(tw_->widget(4))->getRules(); |
| 423 |
|
|
|
| 424 |
|
✗ |
HppManipulationWidgetsPlugin::NamesPair handles = convertMap(handlesMap); |
| 425 |
|
✗ |
HppManipulationWidgetsPlugin::NamesPair shapes = convertMap(shapesMap); |
| 426 |
|
|
try { |
| 427 |
|
✗ |
hpp_->graph()->deleteGraph("constraints"); |
| 428 |
|
✗ |
} catch (const hpp::Error&) { |
| 429 |
|
|
} |
| 430 |
|
|
// TODO the return value is never deleted. |
| 431 |
|
✗ |
std::cout << "graph.buildGenericGraph(robot, 'graph', "; |
| 432 |
|
✗ |
print(grippers.in()); |
| 433 |
|
✗ |
std::cout << ", "; |
| 434 |
|
✗ |
print(handles.first); |
| 435 |
|
✗ |
std::cout << ", "; |
| 436 |
|
✗ |
print(handles.second); |
| 437 |
|
✗ |
std::cout << ", "; |
| 438 |
|
✗ |
print(shapes.second); |
| 439 |
|
✗ |
std::cout << ", "; |
| 440 |
|
✗ |
print(envNames.in()); |
| 441 |
|
✗ |
std::cout << ", "; |
| 442 |
|
✗ |
print(rules.in()); |
| 443 |
|
✗ |
std::cout << ")" << std::endl; |
| 444 |
|
✗ |
gepetto::gui::MainWindow* main = gepetto::gui::MainWindow::instance(); |
| 445 |
|
✗ |
hpp_->graph()->autoBuild("constraints", grippers.in(), handles.first, |
| 446 |
|
|
handles.second, shapes.second, envNames.in(), |
| 447 |
|
|
rules.in()); |
| 448 |
|
✗ |
hpp_->graph()->initialize(); |
| 449 |
|
✗ |
main->log("Built and initialized graph"); |
| 450 |
|
✗ |
graphBuilder_->close(); |
| 451 |
|
|
} |
| 452 |
|
|
|
| 453 |
|
✗ |
void HppManipulationWidgetsPlugin::autoBuildGraph() { |
| 454 |
|
✗ |
if (!hpp_) return; |
| 455 |
|
✗ |
if (graphBuilder_ == NULL) { |
| 456 |
|
✗ |
graphBuilder_ = new QDialog(NULL, Qt::Dialog); |
| 457 |
|
✗ |
tw_ = new QTabWidget(graphBuilder_); |
| 458 |
|
✗ |
graphBuilder_->setLayout(new QVBoxLayout(graphBuilder_)); |
| 459 |
|
✗ |
graphBuilder_->layout()->addWidget(tw_); |
| 460 |
|
|
|
| 461 |
|
|
QListWidget* lw; |
| 462 |
|
|
QListWidget* grippers; |
| 463 |
|
|
QListWidget* handles; |
| 464 |
|
✗ |
QPushButton* button = new QPushButton("Confirm", tw_); |
| 465 |
|
|
|
| 466 |
|
✗ |
connect(button, SIGNAL(clicked()), SLOT(buildGraph())); |
| 467 |
|
✗ |
hpp::Names_t_var n; |
| 468 |
|
✗ |
n = hpp_->problem()->getAvailable("Gripper"); |
| 469 |
|
✗ |
QStringList l; |
| 470 |
|
✗ |
for (unsigned i = 0; i < n->length(); i++) { |
| 471 |
|
✗ |
l << QString(n[i].in()); |
| 472 |
|
|
} |
| 473 |
|
✗ |
lw = new QListWidget(tw_); |
| 474 |
|
✗ |
lw->addItems(l); |
| 475 |
|
✗ |
lw->setSelectionMode(QAbstractItemView::ExtendedSelection); |
| 476 |
|
✗ |
tw_->addTab(lw, "Grippers"); |
| 477 |
|
✗ |
grippers = lw; |
| 478 |
|
|
|
| 479 |
|
✗ |
n = hpp_->problem()->getAvailable("Handle"); |
| 480 |
|
✗ |
l.clear(); |
| 481 |
|
✗ |
for (unsigned i = 0; i < n->length(); i++) { |
| 482 |
|
✗ |
l << QString(n[i].in()); |
| 483 |
|
|
} |
| 484 |
|
✗ |
QWidget* widget = new QWidget(tw_); |
| 485 |
|
✗ |
QVBoxLayout* box = new QVBoxLayout(widget); |
| 486 |
|
✗ |
box->addWidget(new QLabel( |
| 487 |
|
✗ |
"The objects not selected will be locked in their current position.")); |
| 488 |
|
✗ |
lw = new QListWidget(tw_); |
| 489 |
|
✗ |
box->addWidget(lw); |
| 490 |
|
✗ |
lw->addItems(l); |
| 491 |
|
✗ |
lw->setSelectionMode(QAbstractItemView::ExtendedSelection); |
| 492 |
|
✗ |
tw_->addTab(widget, "Handles"); |
| 493 |
|
✗ |
handles = lw; |
| 494 |
|
|
|
| 495 |
|
✗ |
n = hpp_->problem()->getRobotContactNames(); |
| 496 |
|
✗ |
l.clear(); |
| 497 |
|
✗ |
for (unsigned i = 0; i < n->length(); i++) { |
| 498 |
|
✗ |
l << QString(n[i].in()); |
| 499 |
|
|
} |
| 500 |
|
✗ |
lw = new QListWidget(tw_); |
| 501 |
|
✗ |
lw->addItems(l); |
| 502 |
|
✗ |
lw->setSelectionMode(QAbstractItemView::ExtendedSelection); |
| 503 |
|
✗ |
tw_->addTab(lw, "Robot Contacts"); |
| 504 |
|
|
|
| 505 |
|
✗ |
n = hpp_->problem()->getEnvironmentContactNames(); |
| 506 |
|
✗ |
l.clear(); |
| 507 |
|
✗ |
for (unsigned i = 0; i < n->length(); i++) { |
| 508 |
|
✗ |
l << QString(n[i].in()); |
| 509 |
|
|
} |
| 510 |
|
✗ |
lw = new QListWidget(tw_); |
| 511 |
|
✗ |
lw->addItems(l); |
| 512 |
|
✗ |
lw->setSelectionMode(QAbstractItemView::ExtendedSelection); |
| 513 |
|
✗ |
tw_->addTab(lw, "Environments Contacts"); |
| 514 |
|
|
|
| 515 |
|
✗ |
LinkWidget* lWidget = new LinkWidget(grippers, handles, tw_); |
| 516 |
|
✗ |
tw_->addTab(lWidget, "Rules"); |
| 517 |
|
|
|
| 518 |
|
✗ |
tw_->setCornerWidget(button, Qt::BottomRightCorner); |
| 519 |
|
|
} |
| 520 |
|
✗ |
graphBuilder_->show(); |
| 521 |
|
|
} |
| 522 |
|
|
|
| 523 |
|
|
#if (QT_VERSION < QT_VERSION_CHECK(5, 0, 0)) |
| 524 |
|
|
Q_EXPORT_PLUGIN2(hppmanipulationwidgetsplugin, HppManipulationWidgetsPlugin) |
| 525 |
|
|
#endif |
| 526 |
|
|
} // namespace gui |
| 527 |
|
|
} // namespace hpp |
| 528 |
|
|
|