Line |
Branch |
Exec |
Source |
1 |
|
|
// |
2 |
|
|
// Copyright (c) CNRS |
3 |
|
|
// Authors: Joseph Mirabel and Heidy Dallard |
4 |
|
|
// |
5 |
|
|
|
6 |
|
|
#include "hppwidgetsplugin/jointtreewidget.hh" |
7 |
|
|
|
8 |
|
|
#include <gepetto/viewer/group-node.h> |
9 |
|
|
#include <omniORB4/CORBA.h> |
10 |
|
|
|
11 |
|
|
#include <QMenu> |
12 |
|
|
#include <gepetto/gui/action-search-bar.hh> |
13 |
|
|
#include <gepetto/gui/bodytreewidget.hh> |
14 |
|
|
#include <gepetto/gui/mainwindow.hh> |
15 |
|
|
#include <gepetto/gui/windows-manager.hh> |
16 |
|
|
|
17 |
|
|
#include "hppwidgetsplugin/ui_jointtreewidget.h" |
18 |
|
|
#if GEPETTO_GUI_HAS_PYTHONQT |
19 |
|
|
#include <gepetto/gui/pythonwidget.hh> |
20 |
|
|
#endif |
21 |
|
|
|
22 |
|
|
#include "hppwidgetsplugin/joint-action.hh" |
23 |
|
|
#include "hppwidgetsplugin/joint-tree-item.hh" |
24 |
|
|
#include "hppwidgetsplugin/jointbounddialog.hh" |
25 |
|
|
#include "hppwidgetsplugin/transformwidget.hh" |
26 |
|
|
|
27 |
|
|
using CORBA::ULong; |
28 |
|
|
|
29 |
|
|
namespace hpp { |
30 |
|
|
namespace gui { |
31 |
|
|
using gepetto::gui::ActionSearchBar; |
32 |
|
|
using gepetto::gui::MainWindow; |
33 |
|
|
|
34 |
|
✗ |
JointTreeWidget::JointTreeWidget(HppWidgetsPlugin* plugin, QWidget* parent) |
35 |
|
|
: QWidget(parent), |
36 |
|
✗ |
plugin_(plugin), |
37 |
|
✗ |
ui_(new ::Ui::JointTreeWidget), |
38 |
|
✗ |
model_(new QStandardItemModel), |
39 |
|
✗ |
dock_(NULL) { |
40 |
|
✗ |
ui_->setupUi(this); |
41 |
|
✗ |
ui_->jointTree->setModel(model_); |
42 |
|
✗ |
ui_->jointTree->setItemDelegate( |
43 |
|
✗ |
new JointItemDelegate(ui_->button_forceVelocity, plugin_, |
44 |
|
✗ |
gepetto::gui::MainWindow::instance())); |
45 |
|
✗ |
reset(); |
46 |
|
✗ |
initSearchActions(); |
47 |
|
|
|
48 |
|
✗ |
connect(ui_->jointTree, SIGNAL(customContextMenuRequested(QPoint)), |
49 |
|
|
SLOT(customContextMenu(QPoint))); |
50 |
|
✗ |
connect(ui_->jointTree, SIGNAL(expanded(QModelIndex)), |
51 |
|
|
SLOT(resize(QModelIndex))); |
52 |
|
✗ |
connect(ui_->jointTree->selectionModel(), |
53 |
|
|
SIGNAL(currentChanged(QModelIndex, QModelIndex)), |
54 |
|
|
SLOT(currentJointChanged(QModelIndex, QModelIndex))); |
55 |
|
|
} |
56 |
|
|
|
57 |
|
✗ |
JointTreeWidget::~JointTreeWidget() { delete ui_; } |
58 |
|
|
|
59 |
|
✗ |
void JointTreeWidget::initSearchActions() { |
60 |
|
✗ |
ActionSearchBar* asb = MainWindow::instance()->actionSearchBar(); |
61 |
|
|
JointAction* a; |
62 |
|
|
|
63 |
|
✗ |
a = new JointAction(tr("Move &joint..."), this, this); |
64 |
|
✗ |
connect(a, SIGNAL(triggered(std::string)), |
65 |
|
|
SLOT(openJointMoveDialog(std::string))); |
66 |
|
✗ |
asb->addAction(a); |
67 |
|
|
|
68 |
|
✗ |
a = new JointAction(tr("Set &bounds..."), this, this); |
69 |
|
✗ |
connect(a, SIGNAL(triggered(std::string)), |
70 |
|
|
SLOT(openJointBoundDialog(std::string))); |
71 |
|
✗ |
asb->addAction(a); |
72 |
|
|
} |
73 |
|
|
|
74 |
|
✗ |
void JointTreeWidget::dockWidget(QDockWidget* dock) { dock_ = dock; } |
75 |
|
|
|
76 |
|
✗ |
std::string JointTreeWidget::selectedJoint() const { |
77 |
|
✗ |
QItemSelectionModel* sm = ui_->jointTree->selectionModel(); |
78 |
|
✗ |
JointTreeItem* item = NULL; |
79 |
|
✗ |
if (sm->currentIndex().isValid()) { |
80 |
|
✗ |
item = |
81 |
|
✗ |
dynamic_cast<JointTreeItem*>(model_->itemFromIndex(sm->currentIndex())); |
82 |
|
✗ |
if (item != NULL) return item->name(); |
83 |
|
|
} |
84 |
|
✗ |
return std::string(); |
85 |
|
|
} |
86 |
|
|
|
87 |
|
✗ |
QString JointTreeWidget::getSelectedJoint() const { |
88 |
|
✗ |
return QString::fromStdString(selectedJoint()); |
89 |
|
|
} |
90 |
|
|
|
91 |
|
✗ |
void JointTreeWidget::customContextMenu(const QPoint& pos) { |
92 |
|
✗ |
QModelIndex index = ui_->jointTree->indexAt(pos); |
93 |
|
✗ |
if (index.isValid()) { |
94 |
|
✗ |
QMenu contextMenu(tr("Node"), this); |
95 |
|
|
JointTreeItem* item = |
96 |
|
✗ |
dynamic_cast<JointTreeItem*>(model_->itemFromIndex(index)); |
97 |
|
✗ |
if (!item) return; |
98 |
|
✗ |
contextMenu.addActions(item->actions()); |
99 |
|
✗ |
MainWindow* main = MainWindow::instance(); |
100 |
|
✗ |
foreach ( |
101 |
|
|
gepetto::gui::JointModifierInterface* adi, |
102 |
|
|
main->pluginManager()->get<gepetto::gui::JointModifierInterface>()) { |
103 |
|
✗ |
if (!adi) continue; |
104 |
|
✗ |
contextMenu.addAction(adi->action(item->name())); |
105 |
|
|
} |
106 |
|
|
#if GEPETTO_GUI_HAS_PYTHONQT |
107 |
|
|
QVariantList jass = main->pythonWidget()->callPluginMethod( |
108 |
|
✗ |
"getJointActions", QVariantList() << item->text()); |
109 |
|
✗ |
foreach (QVariant jas, jass) { |
110 |
|
✗ |
if (!jas.canConvert(QVariant::List)) { |
111 |
|
✗ |
qDebug() << "Could not convert to QVariantList" << jas; |
112 |
|
✗ |
continue; |
113 |
|
|
} |
114 |
|
✗ |
foreach (QVariant ja, jas.toList()) { |
115 |
|
✗ |
QAction* action = qobject_cast<QAction*>(ja.value<QObject*>()); |
116 |
|
✗ |
if (action) |
117 |
|
✗ |
contextMenu.addAction(action); |
118 |
|
|
else { |
119 |
|
✗ |
qDebug() << "Could not convert to QAction" << ja; |
120 |
|
|
} |
121 |
|
|
} |
122 |
|
|
} |
123 |
|
|
#endif |
124 |
|
✗ |
contextMenu.exec(ui_->jointTree->mapToGlobal(pos)); |
125 |
|
✗ |
return; |
126 |
|
|
} |
127 |
|
|
} |
128 |
|
|
|
129 |
|
✗ |
JointTreeItem* JointTreeWidget::buildJointTreeItem(const char* name, |
130 |
|
|
ULong& rkConfig, |
131 |
|
|
ULong& rkVel) { |
132 |
|
✗ |
gepetto::gui::MainWindow* main = gepetto::gui::MainWindow::instance(); |
133 |
|
✗ |
HppWidgetsPlugin::JointElement& je = plugin_->jointMap()[name]; |
134 |
|
✗ |
JointTreeItem::NodesPtr_t nodes(je.bodyNames.size()); |
135 |
|
✗ |
for (std::size_t i = 0; i < je.bodyNames.size(); ++i) { |
136 |
|
✗ |
nodes[i] = main->osg()->getNode(je.bodyNames[i]); |
137 |
|
|
// TODO I do not remember why this is important... |
138 |
|
✗ |
if (!nodes[i]) nodes[i] = main->osg()->getGroup(je.bodyNames[i]); |
139 |
|
|
} |
140 |
|
✗ |
CORBA::Long nbCfg = plugin_->client()->robot()->getJointConfigSize(name); |
141 |
|
✗ |
CORBA::Long nbDof = plugin_->client()->robot()->getJointNumberDof(name); |
142 |
|
|
JointTreeItem* j; |
143 |
|
✗ |
if (nbDof > 0) { |
144 |
|
✗ |
hpp::floatSeq_var c = plugin_->client()->robot()->getJointConfig(name); |
145 |
|
✗ |
hpp::floatSeq_var b = plugin_->client()->robot()->getJointBounds(name); |
146 |
|
✗ |
j = new JointTreeItem(name, rkConfig, rkVel, c.in(), b.in(), nbDof, nodes); |
147 |
|
✗ |
} else { |
148 |
|
✗ |
j = new JointTreeItem(name, rkConfig, rkVel, hpp::floatSeq(), |
149 |
|
✗ |
hpp::floatSeq(), nbDof, nodes); |
150 |
|
|
} |
151 |
|
✗ |
je.item = j; |
152 |
|
✗ |
j->setupActions(plugin_); |
153 |
|
✗ |
rkConfig += nbCfg; |
154 |
|
✗ |
rkVel += nbDof; |
155 |
|
✗ |
return j; |
156 |
|
|
} |
157 |
|
|
|
158 |
|
✗ |
void JointTreeWidget::selectJoint(const std::string& jointName) { |
159 |
|
|
HppWidgetsPlugin::JointMap::const_iterator itj = |
160 |
|
✗ |
plugin_->jointMap().find(jointName); |
161 |
|
✗ |
if (itj == plugin_->jointMap().constEnd()) return; |
162 |
|
✗ |
const HppWidgetsPlugin::JointElement& je = itj.value(); |
163 |
|
✗ |
if (!je.item) return; |
164 |
|
✗ |
qDebug() << "Selected joint: " << QString::fromStdString(je.name); |
165 |
|
✗ |
ui_->jointTree->clearSelection(); |
166 |
|
✗ |
ui_->jointTree->setCurrentIndex(je.item->index()); |
167 |
|
|
} |
168 |
|
|
|
169 |
|
✗ |
void JointTreeWidget::openJointBoundDialog(const std::string jointName) { |
170 |
|
|
try { |
171 |
|
|
hpp::floatSeq_var bounds = |
172 |
|
✗ |
plugin_->client()->robot()->getJointBounds(jointName.c_str()); |
173 |
|
|
int nbCfg = |
174 |
|
✗ |
plugin_->client()->robot()->getJointConfigSize(jointName.c_str()); |
175 |
|
✗ |
if (nbCfg > 0) { |
176 |
|
✗ |
JointBoundDialog dialog(QString::fromStdString(jointName), nbCfg); |
177 |
|
✗ |
dialog.setBounds(bounds.in()); |
178 |
|
✗ |
if (dialog.exec() == QDialog::Accepted) { |
179 |
|
✗ |
dialog.getBounds(bounds.inout()); |
180 |
|
✗ |
plugin_->client()->robot()->setJointBounds(jointName.c_str(), |
181 |
|
|
bounds.in()); |
182 |
|
|
} |
183 |
|
|
} |
184 |
|
✗ |
} catch (const hpp::Error& e) { |
185 |
|
✗ |
gepetto::gui::MainWindow::instance()->logError( |
186 |
|
✗ |
QString::fromLocal8Bit(e.msg)); |
187 |
|
✗ |
return; |
188 |
|
|
} |
189 |
|
|
} |
190 |
|
|
|
191 |
|
✗ |
void JointTreeWidget::moveJoint(hpp::Transform__slice* transform, |
192 |
|
|
std::string const& jointName) { |
193 |
|
✗ |
plugin_->client()->robot()->setJointPositionInParentFrame(jointName.c_str(), |
194 |
|
|
transform); |
195 |
|
✗ |
gepetto::gui::MainWindow::instance()->requestApplyCurrentConfiguration(); |
196 |
|
|
} |
197 |
|
|
|
198 |
|
✗ |
void JointTreeWidget::openJointMoveDialog(const std::string jointName) { |
199 |
|
|
try { |
200 |
|
|
TransformWidget* d = new TransformWidget( |
201 |
|
✗ |
plugin_->client()->robot()->getJointPositionInParentFrame( |
202 |
|
|
jointName.c_str()), |
203 |
|
✗ |
jointName, this); |
204 |
|
|
|
205 |
|
✗ |
d->show(); |
206 |
|
✗ |
connect(d, SIGNAL(valueChanged(hpp::Transform__slice*, std::string const&)), |
207 |
|
|
SLOT(moveJoint(hpp::Transform__slice*, std::string const&))); |
208 |
|
✗ |
} catch (const hpp::Error& e) { |
209 |
|
✗ |
gepetto::gui::MainWindow::instance()->logError( |
210 |
|
✗ |
QString::fromLocal8Bit(e.msg)); |
211 |
|
✗ |
return; |
212 |
|
|
} |
213 |
|
|
} |
214 |
|
|
|
215 |
|
✗ |
void JointTreeWidget::reload() { |
216 |
|
✗ |
reset(); |
217 |
|
✗ |
plugin_->jointMap().clear(); |
218 |
|
|
try { |
219 |
|
✗ |
CORBA::String_var robotName = plugin_->client()->robot()->getRobotName(); |
220 |
|
✗ |
plugin_->updateRobotJoints(robotName.in()); |
221 |
|
✗ |
hpp::Names_t_var joints = plugin_->client()->robot()->getAllJointNames(); |
222 |
|
|
typedef std::map<std::string, JointTreeItem*> JointTreeItemMap_t; |
223 |
|
✗ |
JointTreeItemMap_t items; |
224 |
|
✗ |
ULong rkCfg = 0, rkVel = 0; |
225 |
|
✗ |
for (size_t i = 0; i < joints->length(); ++i) { |
226 |
|
✗ |
const char* jname = joints[(ULong)i]; |
227 |
|
✗ |
std::string bjn(joints[0]); |
228 |
|
✗ |
items[jname] = buildJointTreeItem(jname, rkCfg, rkVel); |
229 |
|
|
} |
230 |
|
✗ |
for (JointTreeItemMap_t::const_iterator _jti = items.begin(); |
231 |
|
✗ |
_jti != items.end(); ++_jti) { |
232 |
|
|
CORBA::String_var _pname = |
233 |
|
✗ |
plugin_->client()->robot()->getParentJointName(_jti->first.c_str()); |
234 |
|
✗ |
std::string pname(_pname); |
235 |
|
✗ |
JointTreeItemMap_t::iterator parent = items.find(pname); |
236 |
|
✗ |
if (parent == items.end()) |
237 |
|
✗ |
model_->appendRow(_jti->second); |
238 |
|
|
else |
239 |
|
✗ |
parent->second->appendRow(_jti->second); |
240 |
|
|
} |
241 |
|
✗ |
} catch (hpp::Error& e) { |
242 |
|
✗ |
gepetto::gui::MainWindow::instance()->logError(QString(e.msg)); |
243 |
|
✗ |
return; |
244 |
|
|
} |
245 |
|
|
} |
246 |
|
|
|
247 |
|
✗ |
void JointTreeWidget::reset() { |
248 |
|
✗ |
model_->clear(); |
249 |
|
✗ |
ui_->jointTree->header()->setVisible(true); |
250 |
|
✗ |
QStringList l; |
251 |
|
✗ |
l << "Joint" |
252 |
|
✗ |
<< "Lower bound" |
253 |
|
✗ |
<< "Upper bound"; |
254 |
|
✗ |
model_->setHorizontalHeaderLabels(l); |
255 |
|
✗ |
model_->setColumnCount(3); |
256 |
|
✗ |
ui_->jointTree->setColumnHidden(1, true); |
257 |
|
✗ |
ui_->jointTree->setColumnHidden(2, true); |
258 |
|
|
} |
259 |
|
|
|
260 |
|
✗ |
void JointTreeWidget::resize(const QModelIndex index) { |
261 |
|
|
Q_UNUSED(index); |
262 |
|
✗ |
ui_->jointTree->resizeColumnToContents(0); |
263 |
|
|
} |
264 |
|
|
|
265 |
|
✗ |
void JointTreeWidget::currentJointChanged(const QModelIndex& current, |
266 |
|
|
const QModelIndex& previous) { |
267 |
|
|
Q_UNUSED(previous); |
268 |
|
✗ |
if (current.isValid()) { |
269 |
|
|
JointTreeItem* item = |
270 |
|
✗ |
dynamic_cast<JointTreeItem*>(model_->itemFromIndex(current)); |
271 |
|
✗ |
if (item == NULL) return; |
272 |
|
|
|
273 |
|
|
HppWidgetsPlugin::JointMap::const_iterator itj = |
274 |
|
✗ |
plugin_->jointMap().find(item->name()); |
275 |
|
✗ |
if (itj == plugin_->jointMap().constEnd()) return; |
276 |
|
✗ |
const HppWidgetsPlugin::JointElement& je = itj.value(); |
277 |
|
|
|
278 |
|
✗ |
MainWindow* main = MainWindow::instance(); |
279 |
|
✗ |
for (std::size_t i = 0; i < je.bodyNames.size(); ++i) { |
280 |
|
✗ |
main->bodyTree()->selectBodyByName(je.bodyNames[i]); |
281 |
|
|
} |
282 |
|
|
} |
283 |
|
|
} |
284 |
|
|
} // namespace gui |
285 |
|
|
} // namespace hpp |
286 |
|
|
|