YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
partitem.cpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium
4 * SPDX-License-Identifier: LGPL-2.1-or-later
5 */
6
7#include "partitem.h"
8#include "log.h"
9
10#include <yarp/os/LogStream.h>
11#include <yarp/dev/Drivers.h>
12#include <yarp/dev/PolyDriver.h>
13
14#include <QDebug>
15#include <QEvent>
16#include <QResizeEvent>
17#include <QFileDialog>
18#include <QXmlStreamWriter>
19#include <QXmlStreamAttribute>
20#include <QMessageBox>
21#include <QSettings>
22#include <cmath>
23#include <cstdio>
24
25PartItem::PartItem(std::string robotName, int id, std::string partName, ResourceFinder& _finder,
29 std::string rcb_protocol,
30 QWidget *parent) :
31 QWidget(parent),
32 m_sequenceWindow(nullptr),
33 m_partId(id),
34 m_mixedEnabled(false),
35 m_positionDirectEnabled(false),
36 m_pwmEnabled(false),
37 m_currentEnabled(false),
38 m_currentPidDlg(nullptr),
39 m_part_speedVisible(false),
40 m_part_motorPositionVisible(false),
41 m_part_dutyVisible(false),
42 m_part_currentVisible(false),
43 m_finder(&_finder),
44 m_iMot(nullptr),
45 m_iinfo(nullptr),
46 m_slow_k(0)
47{
48 m_layout = new FlowLayout();
49 setLayout(m_layout);
50
51 //PolyDriver *cartesiandd[MAX_NUMBER_ACTIVATED];
52
53 if (robotName.at(0) == '/') {
54 robotName.erase(0, 1);
55 }
56 if (partName.at(0) == '/') {
57 partName.erase(0, 1);
58 }
59 m_robotPartPort = std::string("/") + robotName +std::string("/") + partName;
60 m_partName = partName;
61 m_robotName = robotName;
62
63 //checking existence of the port
64 int ind = 0;
65 QString portLocalName = QString("/yarpmotorgui%1/%2").arg(ind).arg(m_robotPartPort.c_str());
66
67
69 nameToCheck += "/rpc:o";
70
71 // NameClient &nic=NameClient::getNameClient();
72 yDebug("Checking the existence of: %s \n", nameToCheck.toLatin1().data());
73 // Address adr=nic.queryName(nameToCheck.c_str());
74
75 Contact adr=Network::queryName(nameToCheck.toLatin1().data());
76
77 //Contact c = yarp::os::Network::queryName(portLocalName.c_str());
78 yDebug("ADDRESS is: %s \n", adr.toString().c_str());
79
80 while(adr.isValid()){
81 ind++;
82
83 portLocalName = QString("/yarpmotorgui%1/%2").arg(ind).arg(m_robotPartPort.c_str());
84
86 nameToCheck += "/rpc:o";
87 // adr=nic.queryName(nameToCheck.c_str());
88 adr=Network::queryName(nameToCheck.toLatin1().data());
89 }
90
91 m_interfaceError = false;
92
93 // Initializing the polydriver options and instantiating the polydrivers
94 m_partOptions.put("local", portLocalName.toLatin1().data());
95 m_partOptions.put("device", "remote_controlboard");
96 m_partOptions.put("remote", m_robotPartPort);
97 m_partOptions.put("carrier", rcb_protocol);
98
99 m_partsdd = new PolyDriver();
100
101 // Opening the drivers
102 m_interfaceError = !openPolyDrivers();
103 if (m_interfaceError == true)
104 {
105 yError("Opening PolyDriver for part %s failed...", m_robotPartPort.c_str());
106 QMessageBox::critical(nullptr, "Error opening a device", QString("Error while opening device for part ").append(m_robotPartPort.c_str()));
107 }
108
109 /*********************************************************************/
110 /**************** PartMover Content **********************************/
111
112 if (!m_finder->isNull()){
113 yDebug("Setting a valid finder \n");
114 }
115
116 QString sequence_portname = QString("/yarpmotorgui/%1/sequence:o").arg(partName.c_str());
117 m_sequence_port.open(sequence_portname.toLatin1().data());
118
121
122 if (m_interfaceError == false)
123 {
124 int i = 0;
125 std::string jointname;
127 m_iPos->getAxes(&number_of_joints);
128
129 m_controlModes.resize(number_of_joints); //for (i = 0; i < number_of_joints; i++) m_controlModes = 0;
130 m_refTrajectorySpeeds.resize(number_of_joints);
131 for (i = 0; i < number_of_joints; i++) {
132 m_refTrajectorySpeeds[i] = std::nan("");
133 }
134 m_refTrajectoryPositions.resize(number_of_joints);
135 for (i = 0; i < number_of_joints; i++) {
136 m_refTrajectoryPositions[i] = std::nan("");
137 }
138 m_refTorques.resize(number_of_joints);
139 for (i = 0; i < number_of_joints; i++) {
140 m_refTorques[i] = std::nan("");
141 }
142 m_refVelocitySpeeds.resize(number_of_joints);
143 for (i = 0; i < number_of_joints; i++) {
144 m_refVelocitySpeeds[i] = std::nan("");
145 }
146 m_refVelocityAccelerations.resize(number_of_joints);
147 for (i = 0; i < number_of_joints; i++) {
148 m_refVelocityAccelerations[i] = std::nan("");
149 }
150 m_torques.resize(number_of_joints);
151 for (i = 0; i < number_of_joints; i++) {
152 m_torques[i] = std::nan("");
153 }
154 m_positions.resize(number_of_joints);
155 for (i = 0; i < number_of_joints; i++) {
156 m_positions[i] = std::nan("");
157 }
158 m_speeds.resize(number_of_joints);
159 for (i = 0; i < number_of_joints; i++) {
160 m_speeds[i] = std::nan("");
161 }
162 m_currents.resize(number_of_joints);
163 for (i = 0; i < number_of_joints; i++) {
164 m_currents[i] = std::nan("");
165 }
166 m_motorPositions.resize(number_of_joints);
167 for (i = 0; i < number_of_joints; i++) {
168 m_motorPositions[i] = std::nan("");
169 }
170 m_dutyCycles.resize(number_of_joints);
171 for (i = 0; i < number_of_joints; i++) {
172 m_dutyCycles[i] = std::nan("");
173 }
174 m_done.resize(number_of_joints);
175 m_braked.resize(number_of_joints);
176 for (i = 0; i < number_of_joints; i++) {
177 m_braked[i] = false;
178 }
179 m_interactionModes.resize(number_of_joints);
180
181 bool ret = false;
183 do {
184 ret = m_iencs->getEncoders(m_positions.data());
185 if (!ret) {
186 yError("%s iencs->getEncoders() failed, retrying...\n", partName.c_str());
188 }
189 } while (!ret);
190
191 yInfo("%s iencs->getEncoders() ok!\n", partName.c_str());
192
193 double min_pos = 0;
194 double max_pos = 100;
195 double min_vel = 0;
196 double max_vel = 100;
197 double min_acc = 0;
198 double max_acc = 100;
199 double min_cur = -2.0;
200 double max_cur = +2.0;
201 for (int k = 0; k<number_of_joints; k++)
202 {
203 bool bpl = m_iLim->getLimits(k, &min_pos, &max_pos);
204 bool bvl = m_iLim->getVelLimits(k, &min_vel, &max_vel);
205 bool bcr = m_iCur->getCurrentRange(k, &min_cur, &max_cur);
206 if (bpl == false)
207 {
208 yError() << "Error while getting position limits, part " << partName << " joint " << k;
209 }
210 if (bvl == false || (min_vel == 0 && max_vel == 0))
211 {
212 yError() << "Error while getting velocity limits, part " << partName << " joint " << k;
213 }
214 if (bcr == false || (min_cur == 0 && max_cur == 0))
215 {
216 yError() << "Error while getting current range, part " << partName << " joint " << k;
217 }
218
219 QSettings settings("YARP", "yarpmotorgui");
220 double max_slider_vel = settings.value("velocity_slider_limit", 100.0).toDouble();
221 if (max_vel > max_slider_vel) {
223 }
224
225 m_iinfo->getAxisName(k, jointname);
227 m_iinfo->getJointType(k, jtype);
228
229 Pid myPid(0,0,0,0,0,0);
232
233 auto* joint = new JointItem(k);
234 joint->setJointName(jointname.c_str());
235 joint->setPWMRange(-100.0, 100.0);
236 joint->setCurrentRange(min_cur, max_cur);
237 m_layout->addWidget(joint);
238 joint->setPositionRange(min_pos, max_pos);
239 joint->setVelocityRange(min_vel, max_vel);
240 joint->setAccelerationRange(min_acc, max_acc);
241 joint->setTorqueRange(5.0);
242 joint->setUnits(jtype);
243 joint->enableControlPositionDirect(m_positionDirectEnabled);
244 joint->enableControlMixed(m_mixedEnabled);
245 joint->enableControlPWM(m_pwmEnabled);
246 joint->enableControlCurrent(m_currentEnabled);
247
248 int val_pos_choice = settings.value("val_pos_choice", 0).toInt();
249 int val_vel_choice = settings.value("val_vel_choice", 0).toInt();
250 int val_acc_choice = settings.value("val_acc_choice", 0).toInt();
251 int val_trq_choice = settings.value("val_trq_choice", 0).toInt();
252 int val_cur_choice = settings.value("val_cur_choice", 0).toInt();
253
254 int num_of_pos_decimals = settings.value("num_of_pos_decimals", 3).toInt();
255 int num_of_vel_decimals = settings.value("num_of_vel_decimals", 3).toInt();
256 int num_of_acc_decimals = settings.value("num_of_acc_decimals", 3).toInt();
257 int num_of_trq_decimals = settings.value("num_of_trq_decimals", 3).toInt();
258 int num_of_cur_decimals = settings.value("num_of_cur_decimals", 3).toInt();
259
260 double val_pos_custom_step = settings.value("val_pos_custom_step", 1.0).toDouble();
261 double val_vel_custom_step = settings.value("val_vel_custom_step", 1.0).toDouble();
262 double val_acc_custom_step = settings.value("val_acc_custom_step", 1.0).toDouble();
263 double val_trq_custom_step = settings.value("val_trq_custom_step", 1.0).toDouble();
264 double val_cur_custom_step = settings.value("val_cur_custom_step", 1.0).toDouble();
265
266 onSetPosSliderOptionPI(val_pos_choice, val_pos_custom_step, num_of_pos_decimals);
267 onSetVelSliderOptionPI(val_vel_choice, val_vel_custom_step, num_of_vel_decimals);
268 onSetAccSliderOptionPI(val_acc_choice, val_acc_custom_step, num_of_acc_decimals);
269 onSetTrqSliderOptionPI(val_trq_choice, val_trq_custom_step, num_of_trq_decimals);
270 onSetCurSliderOptionPI(val_cur_choice, val_cur_custom_step, num_of_cur_decimals);
271
272 joint->setEnabledOptions(debug_param_enabled,
275
276 connect(joint, SIGNAL(changeMode(int,JointItem*)), this, SLOT(onJointChangeMode(int,JointItem*)));
277 connect(joint, SIGNAL(changeInteraction(int,JointItem*)), this, SLOT(onJointInteraction(int,JointItem*)));
278 connect(joint, SIGNAL(sliderPosTrajectoryPositionCommand(double, int)), this, SLOT(onSliderPosTrajectoryPositionCommand(double, int)));
279 connect(joint, SIGNAL(sliderPosTrajectoryVelocityCommand(double, int)), this, SLOT(onSliderPosTrajectoryVelocityCommand(double, int)));
280 connect(joint, SIGNAL(sliderVelTrajectoryVelocityCommand(double, int)), this, SLOT(onSliderVelTrajectoryVelocityCommand(double, int)));
281 connect(joint, SIGNAL(sliderVelTrajectoryAccelerationCommand(double, int)), this, SLOT(onSliderVelTrajectoryAccelerationCommand(double, int)));
282 connect(joint, SIGNAL(sliderMixedPositionCommand(double, int)), this, SLOT(onSliderMixedPositionCommand(double, int)));
283 connect(joint, SIGNAL(sliderMixedVelocityCommand(double, int)), this, SLOT(onSliderMixedVelocityCommand(double, int)));
284 connect(joint, SIGNAL(sliderTorqueCommand(double, int)), this, SLOT(onSliderTorqueCommand(double, int)));
285 connect(joint, SIGNAL(sliderDirectPositionCommand(double, int)), this, SLOT(onSliderDirectPositionCommand(double, int)));
286 connect(joint, SIGNAL(sliderPWMCommand(double, int)), this, SLOT(onSliderPWMCommand(double, int)));
287 connect(joint, SIGNAL(sliderCurrentCommand(double, int)), this, SLOT(onSliderCurrentCommand(double, int)));
288 connect(joint, SIGNAL(sliderVelocityDirectCommand(double, int)), this, SLOT(onSliderVelocityDirectCommand(double, int)));
289 connect(joint, SIGNAL(homeClicked(JointItem*)),this,SLOT(onHomeClicked(JointItem*)));
290 connect(joint, SIGNAL(idleClicked(JointItem*)),this,SLOT(onIdleClicked(JointItem*)));
291 connect(joint, SIGNAL(runClicked(JointItem*)),this,SLOT(onRunClicked(JointItem*)));
292 connect(joint, SIGNAL(pidClicked(JointItem*)),this,SLOT(onPidClicked(JointItem*)));
293 connect(joint, SIGNAL(calibClicked(JointItem*)),this,SLOT(onCalibClicked(JointItem*)));
294 }
295 }
296
297 /*********************************************************************/
298 /*********************************************************************/
299
300 m_cycleTimer.setSingleShot(true);
301 m_cycleTimer.setTimerType(Qt::PreciseTimer);
302 connect(&m_cycleTimer, SIGNAL(timeout()), this, SLOT(onCycleTimerTimeout()), Qt::QueuedConnection);
303
304 m_cycleTimeTimer.setSingleShot(true);
305 m_cycleTimeTimer.setTimerType(Qt::PreciseTimer);
306 connect(&m_cycleTimeTimer, SIGNAL(timeout()), this, SLOT(onCycleTimeTimerTimeout()), Qt::QueuedConnection);
307
308
309 m_runTimeTimer.setSingleShot(true);
310 m_runTimeTimer.setTimerType(Qt::PreciseTimer);
311 connect(&m_runTimeTimer, SIGNAL(timeout()), this, SLOT(onRunTimerTimeout()), Qt::QueuedConnection);
312
313 m_runTimer.setSingleShot(true);
314 m_runTimer.setTimerType(Qt::PreciseTimer);
315 connect(&m_runTimer, SIGNAL(timeout()), this, SLOT(onRunTimeout()), Qt::QueuedConnection);
316}
317
319{
320 disconnect(&m_runTimer, SIGNAL(timeout()), this, SLOT(onRunTimeout()));
321 m_runTimer.stop();
322
323 disconnect(&m_runTimeTimer, SIGNAL(timeout()), this, SLOT(onRunTimerTimeout()));
324 m_runTimeTimer.stop();
325
326 disconnect(&m_cycleTimer, SIGNAL(timeout()), this, SLOT(onCycleTimerTimeout()));
327 m_cycleTimer.stop();
328
329 disconnect(&m_cycleTimeTimer, SIGNAL(timeout()), this, SLOT(onCycleTimeTimerTimeout()));
330 m_cycleTimeTimer.stop();
331
332 if (m_sequenceWindow){
333 m_sequenceWindow->hide();
334 delete m_sequenceWindow;
335 }
336
337 for (int i = 0; i<m_layout->count(); i++){
338 auto* joint = (JointItem *)m_layout->itemAt(i)->widget();
339 if(joint){
340 disconnect(joint,SIGNAL(changeMode(int,JointItem*)), this, SLOT(onJointChangeMode(int,JointItem*)));
341 disconnect(joint,SIGNAL(changeInteraction(int,JointItem*)), this, SLOT(onJointInteraction(int,JointItem*)));
342 disconnect(joint,SIGNAL(homeClicked(JointItem*)),this,SLOT(onHomeClicked(JointItem*)));
343 disconnect(joint,SIGNAL(idleClicked(JointItem*)),this,SLOT(onIdleClicked(JointItem*)));
344 disconnect(joint,SIGNAL(runClicked(JointItem*)),this,SLOT(onRunClicked(JointItem*)));
345 disconnect(joint,SIGNAL(pidClicked(JointItem*)),this,SLOT(onPidClicked(JointItem*)));
346 disconnect(joint,SIGNAL(calibClicked(JointItem*)),this,SLOT(onCalibClicked(JointItem*)));
347 delete joint;
348 }
349 }
350
351 if (m_partsdd){
352 m_partsdd->close();
353 delete m_partsdd;
354 m_partsdd = nullptr;
355 }
356}
357
359{
360 m_partsdd->open(m_partOptions);
361 if (!m_partsdd->isValid()) {
362 return false;
363 }
364
365 #ifdef DEBUG_INTERFACE
367 {
369 if(!debugdd->isValid()){
370 yError("Problems opening the debug client!");
371 }
372 } else {
373 debugdd = NULL;
374 }
375 #endif
376 return true;
377}
378
380{
381 yDebug("Initializing interfaces...");
382 //default value for unopened interfaces
383 m_iPos = nullptr;
384 m_iVel = nullptr;
385 m_iVar = nullptr;
386 m_iPosDir = nullptr;
387 m_iVelDir = nullptr;
388 m_iencs = nullptr;
389 m_iAmp = nullptr;
390 m_iPid = nullptr;
391 m_iCur = nullptr;
392 m_iPWM = nullptr;
393 m_iTrq = nullptr;
394 m_iImp = nullptr;
395 m_iLim = nullptr;
396 m_ical = nullptr;
397 m_ictrlmode = nullptr;
398 m_iinteract = nullptr;
399 m_iremCalib = nullptr;
400 m_ijointfault = nullptr;
401}
402
404{
405 yDebug("Opening interfaces...");
406 bool ok = false;
407
408 if (m_partsdd->isValid()) {
409 ok = m_partsdd->view(m_iPid);
410 if(!ok){
411 yError("...iPid was not ok...");
412 }
413 ok &= m_partsdd->view(m_iAmp);
414 if(!ok){
415 yError("...iAmp was not ok...");
416 }
417 ok &= m_partsdd->view(m_iPos);
418 if(!ok){
419 yError("...iPos was not ok...");
420 }
421 ok &= m_partsdd->view(m_iPosDir);
422 if(!ok){
423 yError("...posDirect was not ok...");
424 }
425 ok &= m_partsdd->view(m_iVelDir);
426 if(!ok){
427 yError("...velDirect was not ok...");
428 }
429 ok &= m_partsdd->view(m_iVel);
430 if(!ok){
431 yError("...iVel was not ok...");
432 }
433 ok &= m_partsdd->view(m_iLim);
434 if(!ok){
435 yError("...iLim was not ok...");
436 }
437 ok &= m_partsdd->view(m_iencs);
438 if(!ok){
439 yError("...enc was not ok...");
440 }
441 ok &= m_partsdd->view(m_ical);
442 if(!ok){
443 yError("...cal was not ok...");
444 }
445 ok &= m_partsdd->view(m_iTrq);
446 if(!ok){
447 yError("...trq was not ok...");
448 }
449 ok = m_partsdd->view(m_iPWM);
450 if(!ok){
451 yError("...opl was not ok...");
452 }
453 ok &= m_partsdd->view(m_iImp);
454 if(!ok){
455 yError("...imp was not ok...");
456 }
457 ok &= m_partsdd->view(m_ictrlmode);
458 if(!ok){
459 yError("...ctrlmode2 was not ok...");
460 }
461 ok &= m_partsdd->view(m_iinteract);
462 if(!ok){
463 yError("...iinteract was not ok...");
464 }
465
466 //optional interfaces
467 if (!m_partsdd->view(m_ijointfault))
468 {
469 yWarning("...m_iJointFault was not ok...");
470 }
471 if (!m_partsdd->view(m_ijointbrake))
472 {
473 yWarning("...m_iJointBrake was not ok...");
474 }
475 if (!m_partsdd->view(m_iVar))
476 {
477 yWarning("...iVar was not ok...");
478 }
479 if (!m_partsdd->view(m_iMot))
480 {
481 yWarning("...iMot was not ok...");
482 }
483 if (!m_partsdd->view(m_iremCalib))
484 {
485 yWarning("...remCalib was not ok...");
486 }
487 if (!m_partsdd->view(m_iinfo))
488 {
489 yWarning("...axisInfo was not ok...");
490 }
491 if (!m_partsdd->view(m_iCur))
492 {
493 yWarning("...iCur was not ok...");
494 }
495
496 if (!ok) {
497 yError("Error while acquiring interfaces!");
498 QMessageBox::critical(nullptr,"Problems acquiring interfaces.","Check if interface is running");
499 m_interfaceError = true;
500 }
501 }
502 else
503 {
504 yError("Device driver was not valid!");
505 m_interfaceError = true;
506 }
507
508 return !m_interfaceError;
509}
510
512{
513 return m_interfaceError;
514}
515
517{
518 return m_partName;
519}
520
521void PartItem::onSliderPWMCommand(double pwmVal, int index)
522{
523 m_iPWM->setRefDutyCycle(index, pwmVal);
524}
525
526void PartItem::onSliderCurrentCommand(double currentVal, int index)
527{
528 m_iCur->setRefCurrent(index, currentVal);
529}
530
531void PartItem::onSliderVelTrajectoryVelocityCommand(double speedVal, int index)
532{
533 m_iVel->velocityMove(index, speedVal);
534}
535
536void PartItem::onSliderVelTrajectoryAccelerationCommand(double accVal, int index)
537{
538 m_iVel->setRefAcceleration(index, accVal);
539}
540
541void PartItem::onSliderVelocityDirectCommand(double speedVal, int index)
542{
543 m_iVelDir->setDesiredVelocity(index, speedVal);
544}
545
546void PartItem::onSliderTorqueCommand(double torqueVal, int index)
547{
548 m_iTrq->setRefTorque(index, torqueVal);
549}
550
551void PartItem::onSliderPosTrajectoryVelocityCommand(double trajspeedVal, int index)
552{
553 m_iPos->setRefSpeed(index, trajspeedVal);
554}
555
556
557void PartItem::onSliderDirectPositionCommand(double dirpos, int index)
558{
559 int mode;
560 m_ictrlmode->getControlMode(index, &mode);
562 {
563 m_iPosDir->setPosition(index, dirpos);
564 }
565 else
566 {
567 yWarning("Joint not in position direct mode so cannot send references");
568 }
569}
570
571void PartItem::onDumpAllRemoteVariables()
572{
573 if (m_iVar == nullptr)
574 {
575 return;
576 }
577
578 QString fileName = QFileDialog::getSaveFileName(this, QString("Save Dump for Remote Variables as:"), QDir::homePath()+QString("/RemoteVariablesDump.txt"));
579
580 FILE* dumpfile = fopen(fileName.toStdString().c_str(), "w");
581 if (dumpfile != nullptr)
582 {
583 yarp::os::Bottle keys;
584 if (m_iVar->getRemoteVariablesList(&keys))
585 {
586 std::string s = keys.toString();
587 size_t keys_size = keys.size();
588 for (size_t i = 0; i < keys_size; i++)
589 {
590 std::string key_name;
591 if (keys.get(i).isString())
592 {
594 key_name = keys.get(i).asString();
595 if (m_iVar->getRemoteVariable(key_name, val))
596 {
597 std::string key_value = val.toString();
598 std::string p_value = std::string(key_name).append(" ").append(key_value).append("\n");
599 fputs(p_value.c_str(), dumpfile);
600 }
601 }
602 }
603 }
605 }
606}
607
608
609void PartItem::onSliderPosTrajectoryPositionCommand(double posVal, int index)
610{
611 int mode;
612 m_ictrlmode->getControlMode(index, &mode);
613
614 if ( mode == VOCAB_CM_POSITION)
615 {
616 m_iPos->positionMove(index, posVal);
617 }
618 else
619 {
620 yWarning("Joint not in position mode so cannot send references");
621 }
622}
623
624void PartItem::onSliderMixedPositionCommand(double posVal, int index)
625{
626 int mode;
627 m_ictrlmode->getControlMode(index, &mode);
628
629 if ( mode == VOCAB_CM_MIXED)
630 {
631 m_iPos->positionMove(index, posVal);
632 }
633 else
634 {
635 LOG_ERROR("Joint not in mixed mode so cannot send references");
636 }
637}
638
639void PartItem::onSliderMixedVelocityCommand( double vel, int index)
640{
641 int mode;
642 m_ictrlmode->getControlMode(index, &mode);
643
644 if (mode == VOCAB_CM_MIXED)
645 {
646 m_iVel->velocityMove(index, vel);
647 }
648 else
649 {
650 LOG_ERROR("Joint not in mixed mode so cannot send references");
651 }
652}
653
654void PartItem::onJointInteraction(int interaction,JointItem *joint)
655{
656 const int jointIndex = joint->getJointIndex();
657 switch (interaction) {
659 yInfo("interaction mode of joint %d set to COMPLIANT", jointIndex);
661 break;
662 case JointItem::Stiff:
663 yInfo("interaction mode of joint %d set to STIFF", jointIndex);
665 break;
666 default:
667 break;
668 }
669}
670
671
672void PartItem::onSendPWM(int jointIndex, double pwmVal)
673{
674 double pwm_reference = 0;
675 double current_pwm = 0;
676
677 m_iPWM->setRefDutyCycle(jointIndex, pwmVal);
678
680 m_iPWM->getRefDutyCycle(jointIndex, &pwm_reference); //This is the reference
682 m_iPWM->getDutyCycle(jointIndex, &current_pwm); //This is the real PWM output
683
684 if (m_currentPidDlg){
685 m_currentPidDlg->initPWM(pwm_reference, current_pwm);
686 }
687}
688
689void PartItem::onSendForceOffset(int jointIdex,double force)
690{
691 double offset_val=0;
692
696
697 double off_max=0.0;
698 double off_min=0.0;
700
701 if (m_currentPidDlg)
702 {
703 m_currentPidDlg->initTorqueOffset(offset_val, off_min, off_max);
704 }
705}
706
707void PartItem::onSendStiffness(int jointIdex,double stiff,double damp)
708{
709 double stiff_val=0;
710 double damp_val=0;
711
712 m_iImp->setImpedance(jointIdex, stiff, damp);
715
716 //update the impedance limits
717 double stiff_max=0.0;
718 double stiff_min=0.0;
719 double damp_max=0.0;
720 double damp_min=0.0;
721
723
724 if (m_currentPidDlg)
725 {
726 m_currentPidDlg->initStiffness(stiff_val, stiff_min, stiff_max,
728 }
729
730
731}
732
733void PartItem::onSendTorquePid(int jointIndex,Pid newPid,MotorTorqueParameters newTrqParam)
734{
735 Pid myTrqPid(0,0,0,0,0,0);
737 m_iPid->setPid(VOCAB_PIDTYPE_TORQUE, jointIndex, newPid);
738
739 m_iTrq->setMotorTorqueParams(jointIndex, newTrqParam);
741 m_iPid->getPid(VOCAB_PIDTYPE_TORQUE,jointIndex, &myTrqPid);
742 m_iTrq->getMotorTorqueParams(jointIndex, &TrqParam);
743
744 if (m_currentPidDlg){
745 m_currentPidDlg->initTorque(myTrqPid, TrqParam);
746 }
747}
748
749void PartItem::onSendPositionPid(int jointIndex,Pid newPid)
750{
751 Pid myPosPid(0,0,0,0,0,0);
752 m_iPid->setPid(VOCAB_PIDTYPE_POSITION, jointIndex, newPid);
754 m_iPid->getPid(VOCAB_PIDTYPE_POSITION, jointIndex, &myPosPid);
755
756 if (m_currentPidDlg){
757 m_currentPidDlg->initPosition(myPosPid);
758 }
759}
760
761void PartItem::onSendVelocityPid(int jointIndex, Pid newPid)
762{
763 Pid myVelPid(0, 0, 0, 0, 0, 0);
764 m_iPid->setPid(VOCAB_PIDTYPE_VELOCITY, jointIndex, newPid);
766 m_iPid->getPid(VOCAB_PIDTYPE_VELOCITY, jointIndex, &myVelPid);
767
768 if (m_currentPidDlg){
769 m_currentPidDlg->initVelocity(myVelPid);
770 }
771}
772
773void PartItem::onRefreshPids(int jointIndex)
774{
775 Pid myPosPid(0, 0, 0, 0, 0, 0);
776 Pid myTrqPid(0, 0, 0, 0, 0, 0);
777 Pid myVelPid(0, 0, 0, 0, 0, 0);
778 Pid myCurPid(0, 0, 0, 0, 0, 0);
780 double stiff_val = 0;
781 double damp_val = 0;
782 double stiff_max = 0;
783 double damp_max = 0;
784 double off_max = 0;
785 double stiff_min = 0;
786 double damp_min = 0;
787 double off_min = 0;
788 double impedance_offset_val = 0;
789 double pwm_reference = 0;
790 double current_pwm = 0;
791
793 m_iTrq->getTorqueRange(jointIndex, &off_min, &off_max);
794
795 // Position
796 m_iPid->getPid(VOCAB_PIDTYPE_POSITION, jointIndex, &myPosPid);
798
799 // Velocity
800 m_iPid->getPid(VOCAB_PIDTYPE_VELOCITY, jointIndex, &myVelPid);
802
803 // Current
804 if (m_iCur)
805 {
806 m_iPid->getPid(VOCAB_PIDTYPE_CURRENT, jointIndex, &myCurPid);
808 }
809
810 // Torque
811 m_iPid->getPid(VOCAB_PIDTYPE_TORQUE, jointIndex, &myTrqPid);
812 m_iTrq->getMotorTorqueParams(jointIndex, &motorTorqueParams);
814
815 //Stiff
816 m_iImp->getImpedance(jointIndex, &stiff_val, &damp_val);
817 m_iImp->getImpedanceOffset(jointIndex, &impedance_offset_val);
819
820 // PWM
821 m_iPWM->getRefDutyCycle(jointIndex, &pwm_reference);
822 m_iPWM->getDutyCycle(jointIndex, &current_pwm);
823
824 if (m_currentPidDlg)
825 {
826 m_currentPidDlg->initPosition(myPosPid);
827 m_currentPidDlg->initTorque(myTrqPid, motorTorqueParams);
828 m_currentPidDlg->initVelocity(myVelPid);
829 m_currentPidDlg->initCurrent(myCurPid);
832 m_currentPidDlg->initPWM(pwm_reference, current_pwm);
833 m_currentPidDlg->initRemoteVariables(m_iVar);
834 }
835}
836
837void PartItem::onSendCurrentPid(int jointIndex, Pid newPid)
838{
839 if (m_iCur == nullptr)
840 {
841 yError() << "iCurrent interface not opened";
842 return;
843 }
844 Pid myCurPid(0, 0, 0, 0, 0, 0);
845 m_iPid->setPid(VOCAB_PIDTYPE_CURRENT, jointIndex, newPid);
847 m_iPid->getPid(VOCAB_PIDTYPE_CURRENT, jointIndex, &myCurPid);
848
849 if (m_currentPidDlg){
850 m_currentPidDlg->initCurrent(myCurPid);
851 }
852}
853
854void PartItem::onSendSingleRemoteVariable(std::string key, yarp::os::Bottle val)
855{
856 m_iVar->setRemoteVariable(key, val);
858}
859
860void PartItem::onUpdateAllRemoteVariables()
861{
862 if (m_currentPidDlg){
863 m_currentPidDlg->initRemoteVariables(m_iVar);
864 }
865}
866
867void PartItem::onCalibClicked(JointItem *joint)
868{
869 if (!m_iremCalib)
870 {
871 QMessageBox::critical(this,"Operation not supported", QString("The IRemoteCalibrator interface was not found on this application"));
872 return;
873 }
874
875 if(QMessageBox::question(this,"Question","Do you really want to recalibrate the joint?") != QMessageBox::Yes){
876 return;
877 }
878 if (!m_iremCalib->calibrateSingleJoint(joint->getJointIndex()))
879 {
880 // provide better feedback to user by verifying if the calibrator device was set or not
881 bool isCalib = false;
882 m_iremCalib->isCalibratorDevicePresent(&isCalib);
883 if (!isCalib) {
884 QMessageBox::critical(this,"Calibration failed", QString("No calibrator device was configured to perform this action, please verify that the wrapper config file has the 'Calibrator' keyword in the attach phase"));
885 } else {
886 QMessageBox::critical(this, "Calibration failed", QString("The remote calibrator reported that something went wrong during the calibration procedure"));
887 }
888 }
889
890}
891
892void PartItem::onPidClicked(JointItem *joint)
893{
894 const int jointIndex = joint->getJointIndex();
895 QString jointName = joint->getJointName();
896 m_currentPidDlg = new PidDlg(m_partName.c_str(), jointIndex, jointName);
897 connect(m_currentPidDlg, SIGNAL(sendPositionPid(int, Pid)), this, SLOT(onSendPositionPid(int, Pid)));
898 connect(m_currentPidDlg, SIGNAL(sendVelocityPid(int, Pid)), this, SLOT(onSendVelocityPid(int, Pid)));
899 connect(m_currentPidDlg, SIGNAL(sendCurrentPid(int, Pid)), this, SLOT(onSendCurrentPid(int, Pid)));
900 connect(m_currentPidDlg, SIGNAL(sendSingleRemoteVariable(std::string, yarp::os::Bottle)), this, SLOT(onSendSingleRemoteVariable(std::string, yarp::os::Bottle)));
901 connect(m_currentPidDlg, SIGNAL(updateAllRemoteVariables()), this, SLOT(onUpdateAllRemoteVariables()));
902 connect(m_currentPidDlg, SIGNAL(sendTorquePid(int, Pid, MotorTorqueParameters)), this, SLOT(onSendTorquePid(int, Pid, MotorTorqueParameters)));
903 connect(m_currentPidDlg, SIGNAL(sendStiffness(int, double, double)), this, SLOT(onSendStiffness(int, double, double)));
904 connect(m_currentPidDlg, SIGNAL(sendForceOffset(int, double)), this, SLOT(onSendForceOffset(int, double)));
905 connect(m_currentPidDlg, SIGNAL(sendPWM(int, double)), this, SLOT(onSendPWM(int, double)));
906 connect(m_currentPidDlg, SIGNAL(refreshPids(int)), this, SLOT(onRefreshPids(int)));
907 connect(m_currentPidDlg, SIGNAL(dumpRemoteVariables()), this, SLOT(onDumpAllRemoteVariables()));
908
909 this->onRefreshPids(jointIndex);
910
911 m_currentPidDlg->exec();
912
913 delete m_currentPidDlg;
914 m_currentPidDlg = nullptr;
915}
916
917void PartItem::onRunClicked(JointItem *joint)
918{
919 const int jointIndex = joint->getJointIndex();
920 double posJoint;
921 while (!m_iencs->getEncoder(jointIndex, &posJoint)){
923 }
924
925 m_ictrlmode->setControlMode(jointIndex, VOCAB_CM_POSITION);
926}
927
928void PartItem::onIdleClicked(JointItem *joint)
929{
930 const int jointIndex = joint->getJointIndex();
931 m_ictrlmode->setControlMode(jointIndex, VOCAB_CM_FORCE_IDLE);
932}
933
934void PartItem::onHomeClicked(JointItem *joint)
935{
937 const int jointIndex = joint->getJointIndex();
938 m_iPos->getAxes(&NUMBER_OF_JOINTS);
939
940 this->homeJoint(jointIndex);
941}
942
943void PartItem::onJointChangeMode(int mode,JointItem *joint)
944{
945 const int jointIndex = joint->getJointIndex();
946 switch (mode) {
947 case JointItem::Idle:{
948 yInfo("joint: %d in IDLE mode", jointIndex);
949 if (m_ictrlmode){
950 m_ictrlmode->setControlMode(jointIndex, VOCAB_CM_IDLE);
951 } else {
952 yError("ERROR: cannot do!");
953 }
954 break;
955 }
957 yInfo("joint: %d in POSITION mode", jointIndex);
958 if (m_ictrlmode){
959 m_ictrlmode->setControlMode(jointIndex, VOCAB_CM_POSITION);
960 joint->resetTarget();
961 } else {
962 yError("ERROR: cannot do!");
963 }
964 break;
965 }
967 //if(positionDirectEnabled){
968 yInfo("joint: %d in POSITION DIRECT mode", jointIndex);
969 if (m_ictrlmode){
970 joint->resetTarget();
971 m_ictrlmode->setControlMode(jointIndex, VOCAB_CM_POSITION_DIRECT);
972 } else {
973 yError("ERROR: cannot do!");
974 }
975 break;
976 /*}else{
977 LOG_ERROR("joint: %d in MIXED mode", jointIndex);
978 if(ctrlmode2){
979 ctrlmode2->setControlMode(jointIndex, VOCAB_CM_MIXED);
980 } else {
981 yError("ERROR: cannot do!");
982 }
983 break;
984 }*/
985 }
986 case JointItem::Mixed:{
987 //if(positionDirectEnabled){
988 yInfo("joint: %d in MIXED mode", jointIndex);
989 if (m_ictrlmode){
990 joint->resetTarget();
991 m_ictrlmode->setControlMode(jointIndex, VOCAB_CM_MIXED);
992 } else {
993 yError("ERROR: cannot do!");
994 }
995 break;
996 /*}else{
997 LOG_ERROR("joint: %d in VELOCITY mode", jointIndex);
998 if(ctrlmode2){
999 ctrlmode2->setVelocityMode(jointIndex);
1000 } else {
1001 LOG_ERROR("ERROR: cannot do!");
1002 }
1003 break;
1004 }*/
1005
1006 }
1008 //if(positionDirectEnabled){
1009 yInfo("joint: %d in VELOCITY DIRECT mode", jointIndex);
1010 if (m_ictrlmode)
1011 {
1012 joint->resetTarget();
1013 m_ictrlmode->setControlMode(jointIndex, VOCAB_CM_VELOCITY_DIRECT);
1014 } else {
1015 yError("ERROR: cannot do!");
1016 }
1017 break;
1018 }
1019 case JointItem::Velocity:{
1020 //if(positionDirectEnabled){
1021 yInfo("joint: %d in VELOCITY mode", jointIndex);
1022 if (m_ictrlmode)
1023 {
1024 m_ictrlmode->setControlMode(jointIndex, VOCAB_CM_VELOCITY);
1025 yInfo() << "Changing reference acceleration of joint " << jointIndex << " to 100000";
1026 m_iVel->setRefAcceleration(jointIndex, 100000);
1027 } else {
1028 yError("ERROR: cannot do!");
1029 }
1030 break;
1031// } else {
1032// LOG_ERROR("joint: %d in TORQUE mode", jointIndex);
1033// if(ctrlmode2){
1034// ctrlmode2->setTorqueMode(jointIndex);
1035// } else {
1036// LOG_ERROR("ERROR: cannot do!");
1037// }
1038// break;
1039// }
1040 }
1041
1042 case JointItem::Torque:{
1043 //if(positionDirectEnabled){
1044 yInfo("joint: %d in TORQUE mode", jointIndex);
1045 if (m_ictrlmode){
1046 m_ictrlmode->setControlMode(jointIndex, VOCAB_CM_TORQUE);
1047 } else {
1048 yError("ERROR: cannot do!");
1049 }
1050 break;
1051// } else {
1052// LOG_ERROR("joint: %d in TORQUE mode", jointIndex);
1053// if(ctrlmode2){
1054// ctrlmode2->setTorqueMode(jointIndex);
1055// } else {
1056// LOG_ERROR("ERROR: cannot do!");
1057// }
1058// break;
1059// }
1060
1061 }
1062 case JointItem::Pwm:{
1063 yInfo("joint: %d in PWM mode", jointIndex);
1064 if (m_ictrlmode){
1065 m_ictrlmode->setControlMode(jointIndex, VOCAB_CM_PWM);
1066 } else {
1067 yError("ERROR: cannot do!");
1068 }
1069 break;
1070 }
1071 case JointItem::Current:{
1072 yInfo("joint: %d in CURRENT mode", jointIndex);
1073 if (m_ictrlmode){
1074 m_ictrlmode->setControlMode(jointIndex, VOCAB_CM_CURRENT);
1075 }
1076 else {
1077 yError("ERROR: cannot do!");
1078 }
1079 break;
1080 }
1081 default:
1082 break;
1083 }
1084}
1085
1087{
1088 int count = m_layout->count();
1089
1090
1091 int jointPerLineCount = (w - 20) / (MAX_WIDTH_JOINT + 10);
1092 if(jointPerLineCount > count){
1093 jointPerLineCount = count;
1094 }
1095 if(jointPerLineCount <= 0){
1096 return;
1097 }
1098
1099 int extraSpace = (w - 20) - jointPerLineCount * (MAX_WIDTH_JOINT + 10);
1100
1101
1102
1103 for(int i=0;i<count;i++){
1104 QWidget *widget = m_layout->itemAt(i)->widget();
1105 if(widget){
1106 widget->setMaximumWidth(MAX_WIDTH_JOINT + (extraSpace/jointPerLineCount));
1107 widget->setMinimumWidth(MAX_WIDTH_JOINT + (extraSpace/jointPerLineCount));
1108 }
1109
1110 }
1111}
1112
1114{
1115 return m_layout->count();
1116}
1117
1119{
1121 {
1122 return "";
1123 }
1124
1125 auto* jointWidget = (JointItem*)m_layout->itemAt(joint)->widget();
1126
1127 return jointWidget->getJointName();
1128}
1129
1131{
1132 return (JointItem*)m_layout->itemAt(jointIndex)->widget();
1133}
1134
1136{
1137 if(!isVisible()){
1138 return;
1139 }
1140
1141 resizeWidget(event->size().width());
1142}
1143
1145{
1146 if(event->type() == QEvent::WindowStateChange ){
1147 qDebug() << "State Changed " << width();
1148 int count = m_layout->count();
1149 int jointPerLineCount = (width() - 20) / (MAX_WIDTH_JOINT + 10);
1150
1151 if(jointPerLineCount > count){
1152 jointPerLineCount = count;
1153 }
1154 if(jointPerLineCount <= 0){
1155 return;
1156 }
1157 int extraSpace = (width() - 20) - jointPerLineCount * (MAX_WIDTH_JOINT + 10);
1158
1159
1161
1162 for(int i=0;i<count;i++){
1163 QWidget *widget = m_layout->itemAt(i)->widget();
1164 if(widget){
1165 widget->setMaximumWidth(MAX_WIDTH_JOINT + (extraSpace/jointPerLineCount));
1166 widget->setMinimumWidth(MAX_WIDTH_JOINT + (extraSpace/jointPerLineCount));
1167 }
1168 }
1169 }
1170
1171}
1172
1174{
1175 if (!m_iremCalib)
1176 {
1177 QMessageBox::critical(this,"Operation not supported", QString("The IRemoteCalibrator interface was not found on this application"));
1178 return;
1179 }
1180
1181 if (!m_iremCalib->calibrateWholePart())
1182 {
1183 // provide better feedback to user by verifying if the calibrator device was set or not
1184 bool isCalib = false;
1185 m_iremCalib->isCalibratorDevicePresent(&isCalib);
1186 if (!isCalib) {
1187 QMessageBox::critical(this, "Calibration failed", QString("No calibrator device was configured to perform this action, please verify that the wrapper config file for part %1 has the 'Calibrator' keyword in the attach phase").arg(m_partName.c_str()));
1188 } else {
1189 QMessageBox::critical(this, "Calibration failed", QString("The remote calibrator reported that something went wrong during the calibration procedure"));
1190 }
1191 }
1192}
1193
1194bool PartItem::homeJoint(int jointIndex)
1195{
1196 if (!m_iremCalib)
1197 {
1198 QMessageBox::critical(this, "Operation not supported", QString("The IRemoteCalibrator interface was not found on this application"));
1199 return false;
1200 }
1201
1202 if (!m_iremCalib->homingSingleJoint(jointIndex))
1203 {
1204 // provide better feedback to user by verifying if the calibrator device was set or not
1205 bool isCalib = false;
1206 m_iremCalib->isCalibratorDevicePresent(&isCalib);
1207 if (!isCalib)
1208 {
1209 QMessageBox::critical(this, "Operation failed", QString("No calibrator device was configured to perform this action, please verify that the wrapper config file for part %1 has the 'Calibrator' keyword in the attach phase").arg(m_partName.c_str()));
1210 return false;
1211 }
1212 else
1213 {
1214 QMessageBox::critical(this, "Operation failed", QString("The remote calibrator reported that something went wrong during the calibration procedure"));
1215 return false;
1216 }
1217 }
1218 return true;
1219}
1220
1222{
1223 if (!m_iremCalib)
1224 {
1225 QMessageBox::critical(this, "Operation not supported", QString("The IRemoteCalibrator interface was not found on this application"));
1226 return false;
1227 }
1228
1229 if (!m_iremCalib->homingWholePart())
1230 {
1231 // provide better feedback to user by verifying if the calibrator device was set or not
1232 bool isCalib = false;
1233 m_iremCalib->isCalibratorDevicePresent(&isCalib);
1234 if (!isCalib)
1235 {
1236 QMessageBox::critical(this, "Operation failed", QString("No calibrator device was configured to perform this action, please verify that the wrapper config file for part %1 has the 'Calibrator' keyword in the attach phase").arg(m_partName.c_str()));
1237 return false;
1238 }
1239 else
1240 {
1241 QMessageBox::critical(this, "Operation failed", QString("The remote calibrator reported that something went wrong during the calibration procedure"));
1242 return false;
1243 }
1244 }
1245 return true;
1246}
1247
1249{
1250 bool ok = true;
1251 int NUMBER_OF_JOINTS;
1252 m_iPos->getAxes(&NUMBER_OF_JOINTS);
1253
1254 if (positionElement.isNull()) {
1255 QMessageBox::critical(this, "Operation failed", QString("No custom position supplied in configuration file for part ") + QString(m_partName.c_str()));
1256 return false;
1257 }
1258
1259 //Look for group called m_robotPartPort_Position and m_robotPartPort_Velocity
1260 Bottle xtmp, ytmp;
1261 xtmp = positionElement.findGroup(m_robotPartPort + "_Position");
1262 ok = ok && (xtmp.size() == (size_t) NUMBER_OF_JOINTS + 1);
1263 ytmp = positionElement.findGroup(m_robotPartPort + "_Velocity");
1264 ok = ok && (ytmp.size() == (size_t) NUMBER_OF_JOINTS + 1);
1265
1266 if(ok)
1267 {
1268 for (int jointIndex = 0; jointIndex < NUMBER_OF_JOINTS; jointIndex++)
1269 {
1270 double position = xtmp.get(jointIndex+1).asFloat64();
1271 double velocity = ytmp.get(jointIndex + 1).asFloat64();
1272 m_iPos->setRefSpeed(jointIndex, velocity);
1273 m_iPos->positionMove(jointIndex, position);
1274 }
1275 }
1276 else
1277 {
1278 QMessageBox::critical(this, "Error", QString("Check the number of entries in the group %1").arg(m_robotPartPort.c_str()));
1279 ok = false;
1280 }
1281
1282 return ok;
1283}
1284
1286{
1287 int NUMBER_OF_JOINTS;
1288 m_iPos->getAxes(&NUMBER_OF_JOINTS);
1289
1290 for (int joint=0; joint < NUMBER_OF_JOINTS; joint++){
1291 m_ictrlmode->setControlMode(joint, VOCAB_CM_IDLE);
1292 }
1293}
1294
1296{
1297 if (!m_sequenceWindow){
1298 return false;
1299 }
1300
1301 return m_sequenceWindow->checkAndRun();
1302
1303
1304}
1305
1307{
1308 if (!m_sequenceWindow){
1309 return false;
1310 }
1311
1312 return m_sequenceWindow->checkAndRunTime();
1313
1314
1315}
1316
1318{
1319 if (!m_sequenceWindow){
1320 return false;
1321 }
1322
1323 return m_sequenceWindow->checkAndCycleTimeSeq();
1324}
1325
1327{
1328 if (!m_sequenceWindow){
1329 return false;
1330 }
1331
1332 return m_sequenceWindow->checkAndCycleSeq();
1333}
1334
1336{
1337 int NUMBER_OF_JOINTS;
1338 m_iPos->getAxes(&NUMBER_OF_JOINTS);
1339
1340 for (int joint=0; joint < NUMBER_OF_JOINTS; joint++){
1341 //iencs->getEncoder(joint, &posJoint);
1342 m_ictrlmode->setControlMode(joint, VOCAB_CM_POSITION);
1343 }
1344}
1345
1347{
1349 onOpenSequence();
1350}
1351
1357
1359{
1360 if (m_sequenceWindow)
1361 {
1362 m_sequenceWindow->close();
1363 }
1364}
1365
1367{
1368 if (!m_sequenceWindow){
1369 m_sequenceWindow = new SequenceWindow(m_partName.c_str(), m_layout->count());
1370 connect(m_sequenceWindow, SIGNAL(itemDoubleClicked(int)), this, SLOT(onSequenceWindowDoubleClicked(int)), Qt::DirectConnection);
1371 connect(this, SIGNAL(sendPartJointsValues(int, QList<double>, QList<double>)), m_sequenceWindow, SLOT(onReceiveValues(int, QList<double>, QList<double>)), Qt::DirectConnection);
1372 connect(m_sequenceWindow, SIGNAL(goToPosition(SequenceItem)), this, SLOT(onGo(SequenceItem)));
1373 connect(m_sequenceWindow, SIGNAL(runTime(QList<SequenceItem>)), this, SLOT(onSequenceRunTime(QList<SequenceItem>)), Qt::QueuedConnection);
1374 connect(m_sequenceWindow, SIGNAL(run(QList<SequenceItem>)), this, SLOT(onSequenceRun(QList<SequenceItem>)), Qt::QueuedConnection);
1375 connect(m_sequenceWindow, SIGNAL(saveSequence(QList<SequenceItem>, QString)), this, SLOT(onSaveSequence(QList<SequenceItem>, QString)), Qt::QueuedConnection);
1376 connect(m_sequenceWindow, SIGNAL(openSequence()), this, SLOT(onOpenSequence()));
1377 connect(m_sequenceWindow, SIGNAL(cycle(QList<SequenceItem>)), this, SLOT(onSequenceCycle(QList<SequenceItem>)), Qt::QueuedConnection);
1378 connect(m_sequenceWindow, SIGNAL(cycleTime(QList<SequenceItem>)), this, SLOT(onSequenceCycleTime(QList<SequenceItem>)), Qt::QueuedConnection);
1379 connect(m_sequenceWindow, SIGNAL(stopSequence()), this, SLOT(onStopSequence()), Qt::QueuedConnection);
1380
1381 connect(this, SIGNAL(runTimeSequence()), m_sequenceWindow, SLOT(onRunTimeSequence()));
1382 connect(this, SIGNAL(cycleTimeSequence()), m_sequenceWindow, SLOT(onCycleTimeSequence()));
1383 connect(this, SIGNAL(cycleSequence()), m_sequenceWindow, SLOT(onCycleSequence()));
1384 connect(this, SIGNAL(stoppedSequence()), m_sequenceWindow, SLOT(onStoppedSequence()));
1385 connect(this, SIGNAL(setCurrentIndex(int)), m_sequenceWindow, SLOT(onSetCurrentSequenceIndex(int)));
1386
1387 connect(this,SIGNAL(runTimeSequence()),this,SLOT(onSequenceActivated()));
1388 connect(this,SIGNAL(cycleTimeSequence()),this,SLOT(onSequenceActivated()));
1389 connect(this,SIGNAL(cycleSequence()),this,SLOT(onSequenceActivated()));
1390 connect(this,SIGNAL(stoppedSequence()),this,SLOT(onSequenceStopped()));
1391
1392
1393 }
1394
1395 if (!m_sequenceWindow->isVisible()){
1396 m_sequenceWindow->show();
1397 }else{
1398 m_sequenceWindow->setFocus();
1399 m_sequenceWindow->raise();
1400 m_sequenceWindow->setWindowState(Qt::WindowActive);
1401 }
1402
1403}
1404
1406{
1407 if (!m_sequenceWindow){
1408 return false;
1409 }
1410
1411 return m_sequenceWindow->checkAndGo();
1412}
1414{
1415 m_cycleTimer.stop();
1416 m_runTimer.stop();
1417 m_runTimeTimer.stop();
1418 m_cycleTimeTimer.stop();
1420}
1421
1422void PartItem::onStopSequence()
1423{
1424 stopSequence();
1425}
1426
1427void PartItem::onOpenSequence()
1428{
1429 QString fileName = QFileDialog::getOpenFileName(m_sequenceWindow, QString("Load Sequence for part %1 As").arg(m_partName.c_str()), QDir::homePath());
1430
1431 QFileInfo fInfo(fileName);
1432 if(!fInfo.exists()){
1433 return;
1434 }
1435
1436 QString desiredExtension = QString("pos%1").arg(m_partName.c_str());
1437 QString extension = fInfo.suffix();
1438
1440 QMessageBox::critical(this,"Error Loading The Sequence",
1441 QString("Wrong format (check extensions) of the file associated with: ").arg(m_partName.c_str()));
1442 return;
1443 }
1444
1445 QFile file(fileName);
1446 if (!file.open(QFile::ReadOnly | QFile::Text)){
1447 QString msg = QString("Error: Cannot read file %1: %2").arg(qPrintable(fileName))
1448 .arg(qPrintable(file.errorString()));
1449 QMessageBox::critical(this,"Error Loading The Sequence",msg);
1450 return;
1451 }
1452
1453 QXmlStreamReader reader(&file);
1454 reader.readNext();
1455
1457
1460 while(!reader.atEnd()){
1461 reader.readNext();
1462
1463 if(reader.isStartElement()){
1464 if(reader.name().contains("Sequence_")){ //Sequence_
1465 QXmlStreamAttributes attributes = reader.attributes();
1466 referencePart = attributes.value("ReferencePart").toString();
1467 }
1468
1469 if(reader.name() == "Position"){ //Position
1470 QXmlStreamAttributes attributes = reader.attributes();
1471 int index = attributes.value("Index").toInt();
1472 double timing = attributes.value("Timing").toDouble();
1473 item.setTiming(timing);
1474 item.setSequenceNumber(index);
1475 }
1476
1477 if(reader.name() == "JointPositions"){
1478 QXmlStreamAttributes attributes = reader.attributes();
1479 int count = attributes.value("Count").toInt();
1480
1481 reader.readNext();
1482 for(int i=0; i<count;i++){
1483 reader.readNext();
1484 if(reader.name() == "PosValue"){ //PosValue
1485 double pos = reader.readElementText().toDouble();
1486 item.addPositionValue(pos);
1487 }
1488 reader.readNext();
1489 }
1490
1491 }
1492
1493 if(reader.name() == "JointVelocities"){
1494 QXmlStreamAttributes attributes = reader.attributes();
1495 int count = attributes.value("Count").toInt();
1496
1497 reader.readNext();
1498 for(int i=0; i<count;i++){
1499 reader.readNext();
1500 if(reader.name() == "SpeedValue"){ //SpeedValue
1501 double speed = reader.readElementText().toDouble();
1502 item.addSpeedValue(speed);
1503 }
1504 reader.readNext();
1505 }
1506
1507 }
1508
1509 }
1510
1511 if(reader.isEndElement()){
1512 if(reader.name() == "Position"){
1513 sequenceItems.append(item);
1514 item = SequenceItem();
1515 }
1516 }
1517 }
1518
1519 file.close();
1520
1521 if (reader.hasError())
1522 {
1523 QString msg = QString("Error: Failed to parse file %1: %2").arg(qPrintable(fileName)).arg(qPrintable(reader.errorString()));
1524 QMessageBox::critical(this,"Error Loading The Sequence",msg);
1525 return;
1526 } else if (file.error() != QFile::NoError) {
1527 QString msg = QString("Error: Cannot read file %1: %2").arg(qPrintable(fileName)).arg(qPrintable(file.errorString()));
1528 QMessageBox::critical(this,"Error Loading The Sequence",msg);
1529 return;
1530 }
1531
1532 if (m_sequenceWindow){
1533 m_sequenceWindow->loadSequence(sequenceItems);
1534 }
1535
1536}
1537
1538void PartItem::onSaveSequence(QList<SequenceItem> values, QString fileName)
1539{
1540 if (fileName=="")
1541 {
1542 fileName = QFileDialog::getSaveFileName(this, QString("Save Sequence for part %1 As").arg(m_partName.c_str()), QDir::homePath());
1543 }
1544
1545 if(fileName.isEmpty()){
1546 return;
1547 }
1548
1549 QFileInfo fInfo(fileName);
1550 QString completeFileName = QString("%1/%2.pos%3").arg(fInfo.absolutePath()).arg(fInfo.baseName()).arg(m_partName.c_str());
1551 std::string completeFileName_s = completeFileName.toStdString();
1552
1553 //QFile file(completeFileName);
1554 yInfo("Saving file %s\n", completeFileName_s.c_str());
1555
1556 QFile file(completeFileName);
1557 if(!file.open(QIODevice::WriteOnly)){
1558 return;
1559 }
1560
1561 QXmlStreamWriter writer(&file);
1562 writer.setAutoFormatting(true);
1563 writer.writeStartDocument();
1564
1565 writer.writeStartElement(QString("Sequence_pos%1").arg(m_partName.c_str()));
1566
1567 writer.writeAttribute("TotPositions", QString("%1").arg(values.count()));
1568 writer.writeAttribute("ReferencePart", m_partName.c_str());
1569
1570 for(int i=0;i<values.count();i++){
1572 writer.writeStartElement("Position");
1573 writer.writeAttribute("Index",QString("%1").arg(sequenceItem.getSequenceNumber()));
1574 writer.writeAttribute("Timing",QString("%L1").arg(sequenceItem.getTiming(),0,'f',2));
1575
1576 writer.writeStartElement("JointPositions");
1577 writer.writeAttribute("Count",QString("%1").arg(sequenceItem.getPositions().count()));
1578 for(int j=0;j<sequenceItem.getPositions().count(); j++){
1579 QString s = QString("%L1").arg(sequenceItem.getPositions().at(j),0,'f',2);
1580 writer.writeTextElement("PosValue",s);
1581 }
1582 writer.writeEndElement();
1583
1584 writer.writeStartElement("JointVelocities");
1585 writer.writeAttribute("Count",QString("%1").arg(sequenceItem.getSpeeds().count()));
1586 for(int j=0;j<sequenceItem.getSpeeds().count(); j++){
1587 QString s = QString("%L1").arg(sequenceItem.getSpeeds().at(j),0,'f',2);
1588 writer.writeTextElement("SpeedValue",s);
1589 }
1590 writer.writeEndElement();
1591 writer.writeEndElement();
1592 }
1593 writer.writeEndElement();
1594 writer.writeEndDocument();
1595 file.close();
1596 LOG_INFO("File saved and closed\n");
1597
1598
1599// if(file.open(QIODevice::WriteOnly)){
1600// for(int i=0;i<values.count();i++){
1601// SequenceItem sequenceItem = values.at(i);
1602// QString s = QString("[POSITION%1] \n").arg(sequenceItem.getSequenceNumber());
1603// file.write(s.toLatin1().data(),s.length());
1604
1605// s = QString("jointPositions ");
1606// file.write(s.toLatin1().data(),s.length());
1607
1608// for(int j=0;j<sequenceItem.getPositions().count(); j++){
1609// s = QString("%L1 ").arg(sequenceItem.getPositions().at(j),0,'f',2);
1610// file.write(s.toLatin1().data(),s.length());
1611// }
1612
1613// s = QString("\njointVelocities ");
1614// file.write(s.toLatin1().data(),s.length());
1615// for(int j=0;j<sequenceItem.getSpeeds().count(); j++){
1616// s = QString("%L1 ").arg(sequenceItem.getSpeeds().at(j),0,'f',2);
1617// file.write(s.toLatin1().data(),s.length());
1618// }
1619
1620// s = QString("\ntiming ");
1621// file.write(s.toLatin1().data(),s.length());
1622// s = QString("%L1 \n").arg(sequenceItem.getTiming(),0,'f',2);
1623// file.write(s.toLatin1().data(),s.length());
1624// }
1625// file.flush();
1626// file.close();
1627
1628// LOG_ERROR("File saved and closed\n");
1629// }
1630
1631}
1632
1633void PartItem::onSequenceCycleTime(QList<SequenceItem> values)
1634{
1635 // Remove items after the first timing with value < 0
1636 if (m_cycleTimeTimer.isActive() || m_cycleTimer.isActive() || m_runTimeTimer.isActive() || m_runTimer.isActive()){
1637 return;
1638 }
1639
1640 m_cycleTimeValues.clear();
1641 for(int i=0;i<values.count();i++){
1642 SequenceItem it = values.at(i);
1643 if(it.getTiming() > 0){
1644 m_cycleTimeValues.append(it);
1645 }
1646 }
1647
1649 if (m_cycleTimeValues.count() > 0)
1650 {
1651 vals = m_cycleTimeValues.takeFirst();
1652 m_cycleTimeValues.append(vals);
1653 emit setCurrentIndex(vals.getSequenceNumber());
1654 fixedTimeMove(vals);
1655 m_cycleTimeTimer.start(vals.getTiming() * 1000);
1657 }
1658}
1659
1660void PartItem::onCycleTimeTimerTimeout()
1661{
1662 if (m_cycleTimeValues.count() > 0)
1663 {
1664 SequenceItem vals = m_cycleTimeValues.takeFirst();
1665 m_cycleTimeValues.append(vals);
1666 emit setCurrentIndex(vals.getSequenceNumber());
1667 fixedTimeMove(vals);
1668 m_cycleTimeTimer.start(vals.getTiming() * 1000);
1669 }
1670}
1671
1672void PartItem::onSequenceCycle(QList<SequenceItem> values)
1673{
1674 // Remove items after the first timing with value < 0
1675 if (m_cycleTimeTimer.isActive() || m_cycleTimer.isActive() || m_runTimeTimer.isActive() || m_runTimer.isActive()){
1676 return;
1677 }
1678
1679 m_cycleValues.clear();
1680 for(int i=0;i<values.count();i++){
1681 SequenceItem it = values.at(i);
1682 if(it.getTiming() > 0){
1683 m_cycleValues.append(it);
1684 }
1685 }
1686
1688 if (m_cycleValues.count() > 0){
1689 vals = m_cycleValues.takeFirst();
1690
1691 m_cycleValues.append(vals);
1692
1693 double *cmdPositions = new double[vals.getPositions().count()];
1694 double *cmdVelocities = new double[vals.getSpeeds().count()];
1695
1696 for(int i=0;i<vals.getPositions().count();i++){
1697 cmdPositions[i] = vals.getPositions().at(i);
1698 cmdVelocities[i] = vals.getSpeeds().at(i);
1699 //qDebug() << "vals.getSpeeds().at(i)" << vals.getSpeeds().at(i);
1700 }
1701
1702 emit setCurrentIndex(vals.getSequenceNumber());
1703 //fixedTimeMove(vals.getPositions());
1704 m_iPos->setRefSpeeds(cmdVelocities);
1705 m_iPos->positionMove(cmdPositions);
1706 m_cycleTimer.start(vals.getTiming() * 1000);
1707
1709 }
1710}
1711
1712void PartItem::onCycleTimerTimeout()
1713{
1714 if (m_cycleValues.count() > 0){
1715 SequenceItem vals = m_cycleValues.takeFirst();
1716
1717 m_cycleValues.append(vals);
1718
1719 double *cmdPositions = new double[vals.getPositions().count()];
1720 double *cmdVelocities = new double[vals.getSpeeds().count()];
1721
1722 for(int i=0;i<vals.getPositions().count();i++){
1723 cmdPositions[i] = vals.getPositions().at(i);
1724 cmdVelocities[i] = vals.getSpeeds().at(i);
1725 }
1726
1727 emit setCurrentIndex(vals.getSequenceNumber());
1728 //fixedTimeMove(vals.getPositions());
1729 m_iPos->setRefSpeeds(cmdVelocities);
1730 m_iPos->positionMove(cmdPositions);
1731
1732 m_cycleTimer.start(vals.getTiming() * 1000);
1733 }
1734}
1735
1736void PartItem::onSequenceRun(QList<SequenceItem> values)
1737{
1738 // Remove items after the first timing with value < 0
1739 if (m_cycleTimeTimer.isActive() || m_cycleTimer.isActive() || m_runTimeTimer.isActive() || m_runTimer.isActive()){
1740 return;
1741 }
1742
1743 m_runValues.clear();
1744 for(int i=0;i<values.count();i++){
1745 SequenceItem it = values.at(i);
1746 if(it.getTiming() > 0){
1747 m_runValues.append(it);
1748 }
1749 }
1750
1752 if (m_runValues.count() > 0){
1753 vals = m_runValues.takeFirst();
1754
1755 m_runValues.append(vals);
1756
1757 double *cmdPositions = new double[vals.getPositions().count()];
1758 double *cmdVelocities = new double[vals.getSpeeds().count()];
1759
1760 for(int i=0;i<vals.getPositions().count();i++){
1761 cmdPositions[i] = vals.getPositions().at(i);
1762 cmdVelocities[i] = vals.getSpeeds().at(i);
1763 //qDebug() << "vals.getSpeeds().at(i)" << vals.getSpeeds().at(i);
1764 }
1765
1766 emit setCurrentIndex(vals.getSequenceNumber());
1767 //fixedTimeMove(vals.getPositions());
1768 m_iPos->setRefSpeeds(cmdVelocities);
1769 m_iPos->positionMove(cmdPositions);
1770 m_runTimer.start(vals.getTiming() * 1000);
1771
1772 emit runSequence();
1773 }
1774}
1775void PartItem::onRunTimeout()
1776{
1777 if (m_runValues.count() > 0){
1778 SequenceItem vals = m_runValues.takeFirst();
1779 if(vals.getTiming() < 0){
1781 return;
1782 }
1783 double *cmdPositions = new double[vals.getPositions().count()];
1784 double *cmdVelocities = new double[vals.getSpeeds().count()];
1785
1786 for(int i=0;i<vals.getPositions().count();i++){
1787 cmdPositions[i] = vals.getPositions().at(i);
1788 cmdVelocities[i] = vals.getSpeeds().at(i);
1789 //qDebug() << "vals.getSpeeds().at(i)" << vals.getSpeeds().at(i);
1790 }
1791
1792 emit setCurrentIndex(vals.getSequenceNumber());
1793 //fixedTimeMove(vals.getPositions());
1794 m_iPos->setRefSpeeds(cmdVelocities);
1795 m_iPos->positionMove(cmdPositions);
1796
1797
1798 m_runTimer.start(vals.getTiming() * 1000);
1799 }else{
1801 }
1802}
1803
1804
1805
1806void PartItem::onSequenceRunTime(QList<SequenceItem> values)
1807{
1808 if (m_cycleTimeTimer.isActive() || m_cycleTimer.isActive() || m_runTimeTimer.isActive() || m_runTimer.isActive()){
1809 return;
1810 }
1811
1812 m_runTimeValues.clear();
1813
1814 for(int i=0;i<values.count();i++){
1815 SequenceItem it = values.at(i);
1816 if(it.getTiming() > 0){
1817 m_runTimeValues.append(it);
1818 }
1819 }
1820
1822 if (m_runTimeValues.count() > 0){
1823 vals = m_runTimeValues.takeFirst();
1824
1825 emit setCurrentIndex(vals.getSequenceNumber());
1826 fixedTimeMove(vals);
1827 m_runTimeTimer.start(vals.getTiming() * 1000);
1828
1830 }
1831
1832}
1833
1834void PartItem::onRunTimerTimeout()
1835{
1836 if (m_runTimeValues.count() > 0){
1837 SequenceItem vals = m_runTimeValues.takeFirst();
1838 if(vals.getTiming() < 0){
1840 return;
1841 }
1842 emit setCurrentIndex(vals.getSequenceNumber());
1843 fixedTimeMove(vals);
1844 m_runTimeTimer.start(vals.getTiming() * 1000);
1845 }else{
1847 }
1848}
1849
1850void PartItem::fixedTimeMove(SequenceItem sequence)
1851{
1852 int NUM_JOINTS;
1853 m_iPos->getAxes(&NUM_JOINTS);
1854 auto* cmdPositions = new double[NUM_JOINTS];
1855 auto* cmdVelocities = new double[NUM_JOINTS];
1856 auto* startPositions = new double[NUM_JOINTS];
1857 double cmdTime = sequence.getTiming();
1858
1859 while (!m_iencs->getEncoders(startPositions)){
1861 }
1862
1863
1864 for(int k=0; k<NUM_JOINTS; k++){
1865 cmdVelocities[k] = 0;
1866 cmdPositions[k] = sequence.getPositions().at(k);
1867
1868 if (fabs(startPositions[k] - cmdPositions[k]) > 0.01){
1870 } else {
1871 cmdVelocities[k] = 1.0;
1872 }
1873 }
1874
1875 m_iPos->setRefSpeeds(cmdVelocities);
1876 m_iPos->positionMove(cmdPositions);
1877
1878 m_sequence_port_stamp.update();
1879 m_sequence_port.setEnvelope(m_sequence_port_stamp);
1881 m_sequence_port.write(v);
1882 delete[] cmdVelocities;
1883 delete[] startPositions;
1884 delete[] cmdPositions;
1885 return;
1886}
1887
1888void PartItem::onGo(SequenceItem sequenceItem)
1889{
1890 if(sequenceItem.getPositions().isEmpty() || sequenceItem.getSpeeds().isEmpty())
1891 {
1892 QMessageBox::critical(this,"Error", "Select an entry in the table before performing a movement");
1893 return;
1894 }
1895
1896 int NUMBER_OF_JOINTS;
1897 m_iPos->getAxes(&NUMBER_OF_JOINTS);
1898
1899 for(int i=0;i<NUMBER_OF_JOINTS;i++)
1900 {
1901 m_iPos->setRefSpeed(i, sequenceItem.getSpeeds().at(i));
1902 m_iPos->positionMove(i, sequenceItem.getPositions().at(i));
1903 }
1904}
1905
1906void PartItem::onSequenceActivated()
1907{
1908 for (int i = 0; i<m_layout->count(); i++)
1909 {
1910 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
1911 if(joint){
1912 joint->sequenceActivated();
1913 }
1914 }
1915
1917
1918}
1919
1920void PartItem::onSequenceStopped()
1921{
1922 for (int i = 0; i<m_layout->count(); i++)
1923 {
1924 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
1925 if(joint){
1926 joint->sequenceStopped();
1927 }
1928 }
1930}
1931
1932void PartItem::onSequenceWindowDoubleClicked(int sequenceNum)
1933{
1935 QList<double>speeds;
1936 for (int i = 0; i<m_layout->count(); i++)
1937 {
1938 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
1939 values.append(this->m_positions[i]);
1940 speeds.append(joint->getTrajectoryVelocityValue());
1941 }
1942
1944}
1945
1947{
1948 for (int i = 0; i<m_layout->count(); i++)
1949 {
1950 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
1951 joint->enableControlVelocity(control);
1952 }
1953}
1954
1956{
1957 for (int i = 0; i<m_layout->count(); i++)
1958 {
1959 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
1960 joint->enableControlMixed(control);
1961 }
1962}
1963
1965{
1966 for (int i = 0; i<m_layout->count(); i++)
1967 {
1968 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
1969 joint->enableControlPositionDirect(control);
1970 }
1971}
1972
1974{
1975 for (int i = 0; i<m_layout->count(); i++)
1976 {
1977 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
1978 joint->enableControlPWM(control);
1979 }
1980}
1981
1983{
1984 for (int i = 0; i<m_layout->count(); i++)
1985 {
1986 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
1987 joint->enableControlCurrent(control);
1988 }
1989}
1990
1992{
1993 for (int i = 0; i<m_layout->count(); i++)
1994 {
1995 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
1996 joint->enableControlTorque(control);
1997 }
1998}
1999
2001{
2002 for (int i = 0; i<m_layout->count(); i++)
2003 {
2004 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2005 joint->enableControlVelocityDirect(control);
2006 }
2007}
2008
2010{
2011 m_part_speedVisible = view;
2012 for (int i = 0; i<m_layout->count(); i++)
2013 {
2014 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2015 joint->setSpeedVisible(view);
2016 }
2017}
2018
2020{
2021 m_part_motorPositionVisible = view;
2022 for (int i = 0; i<m_layout->count(); i++)
2023 {
2024 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2025 joint->setMotorPositionVisible(view);
2026 }
2027}
2028
2030{
2031 m_part_dutyVisible = view;
2032 for (int i = 0; i<m_layout->count(); i++)
2033 {
2034 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2035 joint->setDutyVisible(view);
2036 }
2037}
2038
2040{
2041 m_part_currentVisible = view;
2042 for (int i = 0; i<m_layout->count(); i++)
2043 {
2044 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2045 joint->setCurrentsVisible(view);
2046 }
2047}
2048
2050{
2051 for (int i = 0; i<m_layout->count(); i++)
2052 {
2053 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2054 joint->viewPositionTargetBox(ena);
2055 }
2056}
2057
2059{
2060 for (int i = 0; i < m_layout->count(); i++)
2061 {
2062 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2063 joint->viewPositionTargetValue(ena);
2064 }
2065}
2066
2068{
2069 for (int i = 0; i<m_layout->count(); i++)
2070 {
2071 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2072 if (mode==0)
2073 {
2074 joint->enablePositionSliderDoubleAuto();
2075 }
2076 else if(mode ==1)
2077 {
2078 joint->enablePositionSliderDoubleValue(step);
2079 }
2080 else if (mode == 2)
2081 {
2082 joint->enablePositionSliderDoubleValue(1.0);
2083 }
2084 else
2085 {
2086 joint->disablePositionSliderDouble();
2087 }
2088 joint->setNumberOfPositionSliderDecimals(numOfDec);
2089 }
2090}
2092{
2093 for (int i = 0; i<m_layout->count(); i++)
2094 {
2095 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2096 if (mode == 0)
2097 {
2098 joint->enableVelocitySliderDoubleAuto();
2099 }
2100 else if (mode == 1)
2101 {
2102 joint->enableVelocitySliderDoubleValue(step);
2103 }
2104 else if (mode == 2)
2105 {
2106 joint->enableVelocitySliderDoubleValue(1.0);
2107 }
2108 else
2109 {
2110 joint->disableVelocitySliderDouble();
2111 }
2112 joint->setNumberOfVelocitySliderDecimals(numOfDec);
2113 }
2114}
2116{
2117 for (int i = 0; i<m_layout->count(); i++)
2118 {
2119 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2120 if (mode == 0)
2121 {
2122 joint->enableAccelerationSliderDoubleAuto();
2123 }
2124 else if (mode == 1)
2125 {
2126 joint->enableAccelerationSliderDoubleValue(step);
2127 }
2128 else if (mode == 2)
2129 {
2130 joint->enableAccelerationSliderDoubleValue(1.0);
2131 }
2132 else
2133 {
2134 joint->disableAccelerationSliderDouble();
2135 }
2136 joint->setNumberOfAccelerationSliderDecimals(numOfDec);
2137 }
2138}
2140{
2141 for (int i = 0; i<m_layout->count(); i++)
2142 {
2143 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2144 if (mode == 0)
2145 {
2146 joint->enableCurrentSliderDoubleAuto();
2147 }
2148 else if (mode == 1)
2149 {
2150 joint->enableCurrentSliderDoubleValue(step);
2151 }
2152 else if (mode == 2)
2153 {
2154 joint->enableCurrentSliderDoubleValue(1.0);
2155 }
2156 else
2157 {
2158 joint->disableCurrentSliderDouble();
2159 }
2160 joint->setNumberOfCurrentSliderDecimals(numOfDec);
2161 }
2162}
2163
2165{
2166 for (int i = 0; i<m_layout->count(); i++)
2167 {
2168 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2169 if (mode == 0)
2170 {
2171 joint->enableTorqueSliderDoubleAuto();
2172 }
2173 else if(mode == 1)
2174 {
2175 joint->enableTorqueSliderDoubleValue(step);
2176 }
2177 else if(mode == 2)
2178 {
2179 joint->enableTorqueSliderDoubleValue(1.0);
2180 }
2181 else
2182 {
2183 joint->disableTorqueSliderDouble();
2184 }
2185 joint->setNumberOfTorqueSliderDecimals(numOfDec);
2186 }
2187}
2188
2190{
2191 return m_modesList;
2192}
2193
2195{
2196 bool ret = m_ictrlmode->getControlModes(m_controlModes.data());
2197
2198
2199 if(ret==false){
2200 LOG_ERROR("ictrl->getControlMode failed on %s\n", getPartName().c_str());
2201 }
2202
2203 m_modesList.resize(m_layout->count());
2204 for (int k = 0; k < m_layout->count(); k++){
2205 switch (m_controlModes[k])
2206 {
2207 case VOCAB_CM_IDLE:
2208 m_modesList[k] = JointItem::Idle;
2209 break;
2210 case VOCAB_CM_POSITION:
2211 m_modesList[k] = JointItem::Position;
2212 break;
2214 m_modesList[k] = JointItem::PositionDirect;
2215 break;
2216 case VOCAB_CM_MIXED:
2217 m_modesList[k] = JointItem::Mixed;
2218 break;
2219 case VOCAB_CM_VELOCITY:
2220 m_modesList[k] = JointItem::Velocity;
2221 break;
2223 m_modesList[k] = JointItem::VelocityDirect;
2224 break;
2225 case VOCAB_CM_TORQUE:
2226 m_modesList[k] = JointItem::Torque;
2227 break;
2228 case VOCAB_CM_PWM:
2229 m_modesList[k] = JointItem::Pwm;
2230 break;
2231 case VOCAB_CM_CURRENT:
2232 m_modesList[k] = JointItem::Current;
2233 break;
2234 case VOCAB_CM_HW_FAULT:
2235 m_modesList[k] = JointItem::HwFault;
2236 break;
2238 m_modesList[k] = JointItem::Calibrating;
2239 break;
2241 m_modesList[k] = JointItem::CalibDone;
2242 break;
2244 m_modesList[k] = JointItem::NotConfigured;
2245 break;
2247 m_modesList[k] = JointItem::Configured;
2248 break;
2249 default:
2250 case VOCAB_CM_UNKNOWN:
2251 m_modesList[k] = JointItem::Unknown;
2252 break;
2253 }
2254 }
2255}
2256
2258{
2259 bool ret = false;
2260 int number_of_joints=0;
2261 m_iPos->getAxes(&number_of_joints);
2262 if (m_slow_k >= number_of_joints - 1) {
2263 m_slow_k = 0;
2264 } else {
2265 m_slow_k++;
2266 }
2267
2268 if (number_of_joints == 0)
2269 {
2270 LOG_ERROR("Lost connection with the robot. You should save and restart.\n" );
2272
2273 for (int i = 0; i<m_layout->count(); i++){
2274 auto* joint = (JointItem*)m_layout->itemAt(i)->widget();
2275 joint->setJointState(JointItem::Disconnected);
2276 }
2277 return false;
2278 }
2279
2280 // *** update measured encoders, velocity, torques ***
2281 bool b = true;
2282 if (true)
2283 {
2284 b = m_iencs->getEncoders(m_positions.data());
2285 if (!b) { yWarning("Unable to update encoders"); return false; }
2286 }
2287 if (true)
2288 {
2289 b = m_iTrq->getTorques(m_torques.data());
2290 if (!b) { yWarning("Unable to update torques"); }
2291 }
2292 if (this->m_part_currentVisible)
2293 {
2294 b = m_iCur->getCurrents(m_currents.data());
2295 if (!b) { yWarning("Unable to update currents"); }
2296 }
2297 if (this->m_part_speedVisible)
2298 {
2299 b = m_iencs->getEncoderSpeeds(m_speeds.data());
2300 if (!b) { yWarning("Unable to update speeds"); }
2301 }
2302 if (this->m_part_motorPositionVisible)
2303 {
2304 b = m_iMot->getMotorEncoders(m_motorPositions.data());
2305 if (!b) { yWarning("Unable to update motorPositions"); }
2306 }
2307 if (this->m_part_dutyVisible)
2308 {
2309 b = m_iPWM->getDutyCycles(m_dutyCycles.data());
2310 if (!b) { yWarning("Unable to update dutyCycles"); }
2311 }
2312
2313 // *** update checkMotionDone, refTorque, refTrajectorySpeed, refSpeed ***
2314 // (only one at a time in order to save bandwidth)
2315 bool ret_motdone = false;
2316 bool ret_refTrq = false;
2317 bool ret_refPosSpeed = false;
2318 bool ret_refVel = false;
2319 bool ret_refAcc = false;
2320 bool ret_refPos = false;
2321 bool ret_jntbrk = false;
2322
2323 if (m_iPos)
2324 {
2325 bool boolval = true;
2326 m_iPos->checkMotionDone(m_slow_k, &boolval); // using k to save bandwidth
2327 m_done[m_slow_k] = boolval;
2328 }
2329 if (m_ijointbrake)
2330 {
2331 bool boolval = true;
2332 ret_jntbrk = m_ijointbrake->isJointBraked(m_slow_k, boolval);
2333 m_braked[m_slow_k] = boolval;
2334 }
2335 if (m_iTrq)
2336 {
2337 ret_refTrq = m_iTrq->getRefTorque(m_slow_k, &m_refTorques[m_slow_k]); // using k to save bandwidth
2338 }
2339 if (m_iPos)
2340 {
2341 ret_refPosSpeed = m_iPos->getRefSpeed(m_slow_k, &m_refTrajectorySpeeds[m_slow_k]); // using k to save bandwidth
2342 }
2343 if (m_iVel)
2344 {
2345 ret_refVel = m_iVel->getRefVelocity(m_slow_k, &m_refVelocitySpeeds[m_slow_k]); // this interface is missing!
2346 }
2347 if (m_iVel)
2348 {
2349 ret_refAcc = m_iVel->getRefAcceleration(m_slow_k, &m_refVelocityAccelerations[m_slow_k]); // this interface is missing!
2350 }
2351 if (m_iPos)
2352 {
2353 ret_refPos = m_iPos->getTargetPosition(m_slow_k, &m_refTrajectoryPositions[m_slow_k]);
2354 }
2355
2356 //Check return values of methods
2357 if (!ret_refPos)
2358 {
2359 yError() << "Missing Implementation of getTargetPosition()";
2360 }
2361 if (!ret_refVel)
2362 {
2363 yError() << "Missing Implementation of getRefVelocity()";
2364 }
2365 if (!ret_refPosSpeed)
2366 {
2367 yError() << "Missing Implementation of getRefSpeed()";
2368 }
2369 if (!ret_refTrq)
2370 {
2371 yError() << "Missing Implementation of getRefTorque()";
2372 }
2373 if (!ret_motdone)
2374 {
2375 yError() << "Missing Implementation of checkMotionDone()";
2376 }
2377 if (!ret_jntbrk)
2378 {
2379 yWarning() << "Missing Implementation of isJointBraked()";
2380 }
2381
2382 // *** update the widget every cycle ***
2383 for (int jk = 0; jk < number_of_joints; jk++)
2384 {
2385 auto* joint = (JointItem*)m_layout->itemAt(jk)->widget();
2386 if (true) { joint->setPosition(m_positions[jk]); }
2387 else {}
2388 if (true) { joint->setTorque(m_torques[jk]); }
2389 else {}
2390 if (true) { joint->setSpeed(m_speeds[jk]); }
2391 else {}
2392 if (true) { joint->setCurrent(m_currents[jk]); }
2393 else {}
2394 if (true) { joint->setMotorPosition(m_motorPositions[jk]); }
2395 else {}
2396 if (true) { joint->setDutyCycles(m_dutyCycles[jk]); }
2397 else {}
2398 }
2399
2400 // *** update the widget NOT every cycle ***
2401 {
2402 auto* joint_slow_k = (JointItem*)m_layout->itemAt(m_slow_k)->widget();
2403 if (ret_refTrq) { joint_slow_k->setRefTorque(m_refTorques[m_slow_k]); }
2404 else {}
2405 if (ret_refPosSpeed) { joint_slow_k->setPosTrajectory_ReferenceSpeed(m_refTrajectorySpeeds[m_slow_k]); }
2406 else {}
2407 if (ret_refPos) { joint_slow_k->setPosTrajectory_ReferencePosition(m_refTrajectoryPositions[m_slow_k]); }
2408 else {}
2409 if (ret_refVel) { joint_slow_k->setVelTrajectory_ReferenceSpeed(m_refVelocitySpeeds[m_slow_k]); }
2410 else {}
2411 if (ret_refAcc) { joint_slow_k->setVelTrajectory_ReferenceAcceleration(m_refVelocityAccelerations[m_slow_k]); }
2412 else {}
2413 if (ret_motdone) { joint_slow_k->updateMotionDone(m_done[m_slow_k]); }
2414 else {}
2415 if (ret_jntbrk) { joint_slow_k->updateBraked(m_braked[m_slow_k]); }
2416 else {}
2417 }
2418
2419
2420 // *** update the controlMode, interactionMode ***
2421 // this is already done by updateControlMode() (because it also needs to update the tree, not only the single joint widget)
2422 // ret=ctrlmode2->getControlModes(controlModes);
2423 // if(ret==false){
2424 // LOG_ERROR("ictrl->getControlMode failed\n" );
2425 // }
2426 ret = m_iinteract->getInteractionModes(m_interactionModes.data());
2427 if(ret==false){
2428 LOG_ERROR("iint->getInteractionlMode failed\n" );
2429 }
2430
2431 //optional
2432 if (m_ijointfault)
2433 {
2434 for (int k = 0; k < number_of_joints; k++)
2435 {
2436 if (m_controlModes[k]==VOCAB_CM_HW_FAULT)
2437 {
2438 int fault;
2439 std::string message;
2440 if (m_ijointfault->getLastJointFault(k,fault,message))
2441 {
2442 auto* joint_slow_k = (JointItem*)m_layout->itemAt(m_slow_k)->widget();
2443 joint_slow_k->updateJointFault(fault, message);
2444 }
2445 else
2446 {
2447 LOG_ERROR("Unsuccessful call to getLastJointFault()\n");
2448 }
2449 }
2450 }
2451 }
2452
2453
2454 for (int k = 0; k < number_of_joints; k++)
2455 {
2456 auto* joint = (JointItem*)m_layout->itemAt(k)->widget();
2457 switch (m_controlModes[k])
2458 {
2459 case VOCAB_CM_IDLE:
2460 joint->setJointState(JointItem::Idle);
2461 break;
2462 case VOCAB_CM_POSITION:
2463 joint->setJointState(JointItem::Position);
2464 break;
2466 joint->setJointState(JointItem::PositionDirect);
2467 break;
2468 case VOCAB_CM_MIXED:
2469 joint->setJointState(JointItem::Mixed);
2470 break;
2471 case VOCAB_CM_VELOCITY:
2472 joint->setJointState(JointItem::Velocity);
2473 break;
2475 joint->setJointState(JointItem::VelocityDirect);
2476 break;
2477 case VOCAB_CM_TORQUE:
2478 joint->setJointState(JointItem::Torque);
2479 break;
2480 case VOCAB_CM_CURRENT:
2481 {
2482 joint->setJointState(JointItem::Current);
2483 double ref_current = 0;
2484 m_iCur->getRefCurrent(k, &ref_current);
2485 joint->setRefCurrent(ref_current);
2486 break;
2487 }
2488 case VOCAB_CM_PWM:
2489 {
2490 joint->setJointState(JointItem::Pwm);
2491 double ref_duty = 0;
2492 m_iPWM->getRefDutyCycle(k, &ref_duty);
2493 joint->setRefPWM(ref_duty);
2494 break;
2495 }
2496 case VOCAB_CM_HW_FAULT:
2497 joint->setJointState(JointItem::HwFault);
2498 break;
2500 joint->setJointState(JointItem::Calibrating);
2501 break;
2503 joint->setJointState(JointItem::CalibDone);
2504 break;
2506 joint->setJointState(JointItem::NotConfigured);
2507 break;
2509 joint->setJointState(JointItem::Configured);
2510 break;
2511 default:
2512 case VOCAB_CM_UNKNOWN:
2513 joint->setJointState(JointItem::Unknown);
2514 break;
2515 }
2516 switch (m_interactionModes[k])
2517 {
2518 case VOCAB_IM_STIFF:
2519 joint->setJointInteraction(JointItem::Stiff);
2520 break;
2521 case VOCAB_IM_COMPLIANT:
2522 joint->setJointInteraction(JointItem::Compliant);
2523 break;
2524 default:
2525 case VOCAB_IM_UNKNOWN:
2526 //joint->setJointInteraction(JointItem::Stiff); TODO
2527 break;
2528 }
2529 }
2530 return true;
2531}
FeatureMode mode
constexpr yarp::conf::vocab32_t VOCAB_CM_UNKNOWN
constexpr yarp::conf::vocab32_t VOCAB_CM_MIXED
constexpr yarp::conf::vocab32_t VOCAB_CM_TORQUE
constexpr yarp::conf::vocab32_t VOCAB_CM_PWM
constexpr yarp::conf::vocab32_t VOCAB_CM_HW_FAULT
constexpr yarp::conf::vocab32_t VOCAB_CM_VELOCITY_DIRECT
constexpr yarp::conf::vocab32_t VOCAB_CM_IDLE
constexpr yarp::conf::vocab32_t VOCAB_CM_CALIB_DONE
constexpr yarp::conf::vocab32_t VOCAB_CM_NOT_CONFIGURED
constexpr yarp::conf::vocab32_t VOCAB_CM_POSITION
constexpr yarp::conf::vocab32_t VOCAB_CM_CONFIGURED
constexpr yarp::conf::vocab32_t VOCAB_CM_CURRENT
constexpr yarp::conf::vocab32_t VOCAB_CM_POSITION_DIRECT
constexpr yarp::conf::vocab32_t VOCAB_CM_VELOCITY
constexpr yarp::conf::vocab32_t VOCAB_CM_FORCE_IDLE
constexpr yarp::conf::vocab32_t VOCAB_CM_CALIBRATING
bool ret
#define yInfo(...)
Definition Log.h:319
#define yError(...)
Definition Log.h:361
#define yDebug(...)
Definition Log.h:275
#define yWarning(...)
Definition Log.h:340
int SIGNAL(int pid, int signum)
Original license follows:
Definition flowlayout.h:59
QLayoutItem * itemAt(int index) const override
int count() const override
@ PositionDirect
Definition jointitem.h:33
@ Disconnected
Definition jointitem.h:34
@ VelocityDirect
Definition jointitem.h:33
@ Calibrating
Definition jointitem.h:34
@ NotConfigured
Definition jointitem.h:34
void initInterfaces()
Definition partitem.cpp:379
bool openPolyDrivers()
Definition partitem.cpp:358
bool checkAndGo()
void cycleTimeSequence()
bool homePart()
void onEnableControlVelocityDirect(bool control)
bool checkAndRunAllSeq()
void onViewDutyCycles(bool)
void resizeWidget(int w)
bool homeToCustomPosition(const yarp::os::Bottle &positionElement)
void setCurrentIndex(int)
void runTimeSequence()
void idlePart()
JointItem * getJointWidget(int jointIndex)
int getNumberOfJoints()
void onEnableControlCurrent(bool control)
bool getInterfaceError()
Definition partitem.cpp:511
void onSetVelSliderOptionPI(int mode, double step, int numOfDec)
void onViewMotorPositions(bool)
void onEnableControlPWM(bool control)
void runPart()
void onEnableControlVelocity(bool control)
PartItem(std::string robotName, int partId, std::string partName, ResourceFinder &_finder, bool debug_param_enabled, bool speedview_param_enabled, bool enable_calib_all, std::string rcb_protocol, QWidget *parent=0)
Definition partitem.cpp:25
QString getJointName(int joint)
std::string getPartName()
Definition partitem.cpp:516
void onSetCurSliderOptionPI(int mode, double step, int numOfDec)
void onViewPositionTargetValue(bool)
void onViewPositionTargetBox(bool)
bool homeJoint(int joint)
void onViewCurrentValues(bool)
void runSequence()
void onSetTrqSliderOptionPI(int mode, double step, int numOfDec)
void sendPartJointsValues(int, QList< double >, QList< double >)
bool checkAndCycleAllSeq()
void closeSequenceWindow()
bool updatePart()
void onViewSpeedValues(bool)
void openSequenceWindow()
void updateControlMode()
void stopSequence()
void stoppedSequence()
void onEnableControlPositionDirect(bool control)
void saveSequence(QString global_filename)
void resizeEvent(QResizeEvent *event) override
void changeEvent(QEvent *event) override
void onEnableControlTorque(bool control)
void loadSequence()
void sequenceStopped()
const QVector< JointItem::JointState > & getPartModes()
void cycleSequence()
void onEnableControlMixed(bool control)
void onSetPosSliderOptionPI(int mode, double step, int numOfDec)
void sequenceActivated()
bool checkAndRunTimeAllSeq()
bool checkAndCycleTimeAllSeq()
void onSetAccSliderOptionPI(int mode, double step, int numOfDec)
void calibratePart()
bool openInterfaces()
Definition partitem.cpp:403
void initVelocity(Pid myPid)
Definition piddlg.cpp:154
void initPosition(Pid myPid)
Definition piddlg.cpp:124
void initTorque(Pid myPid, MotorTorqueParameters TorqueParam)
Definition piddlg.cpp:184
void initTorqueOffset(double curForceVal, double minForce, double maxForce)
Definition piddlg.cpp:344
void initCurrent(Pid myPid)
Definition piddlg.cpp:362
void initStiffness(double curStiffVal, double minStiff, double maxStiff, double curDampVal, double minDamp, double maxDamp)
Definition piddlg.cpp:330
void initRemoteVariables(IRemoteVariables *iVar)
Definition piddlg.cpp:264
void initPWM(double pwmVal, double pwm)
Definition piddlg.cpp:354
void save(QString global_filename)
void loadSequence(QList< SequenceItem >)
bool view(T *&x)
Get an interface to the device driver.
virtual bool getAxisName(int axis, std::string &name)=0
virtual bool getJointType(int axis, yarp::dev::JointTypeEnum &type)
Definition IAxisInfo.h:63
virtual bool getVelLimits(int axis, double *min, double *max)=0
Get the software speed limits for a particular axis.
virtual bool getLimits(int axis, double *min, double *max)=0
Get the software limits for a particular axis.
virtual bool setControlMode(const int j, const int mode)=0
Set the current control mode.
virtual bool getControlModes(int *modes)=0
Get the current control mode (multiple joints).
virtual bool getControlMode(int j, int *mode)=0
Get the current control mode.
virtual bool getCurrents(double *currs)=0
Get the instantaneous current measurement for all motors.
virtual bool setRefCurrent(int m, double curr)=0
Set the reference value of the current for a single motor.
virtual bool getCurrentRange(int m, double *min, double *max)=0
Get the full scale of the current measurement for a given motor (e.g.
virtual bool getRefCurrent(int m, double *curr)=0
Get the reference value of the current for a single motor.
virtual bool getEncoder(int j, double *v)=0
Read the value of an encoder.
virtual bool getEncoders(double *encs)=0
Read the position of all axes.
virtual bool getEncoderSpeeds(double *spds)=0
Read the instantaneous speed of all axes.
virtual bool setImpedance(int j, double stiffness, double damping)=0
Set current impedance gains (stiffness,damping) for a specific joint.
virtual bool getImpedanceOffset(int j, double *offset)=0
Get current force Offset for a specific joint.
virtual bool setImpedanceOffset(int j, double offset)=0
Set current force Offset for a specific joint.
virtual bool getImpedance(int j, double *stiffness, double *damping)=0
Get current impedance gains (stiffness,damping,offset) for a specific joint.
virtual bool getCurrentImpedanceLimit(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp)=0
Get the current impedandance limits for a specific joint.
virtual bool getInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes)=0
Get the current interaction mode of the robot for a set of joints, values can be stiff or compliant.
virtual bool setInteractionMode(int axis, yarp::dev::InteractionModeEnum mode)=0
Set the interaction mode of the robot, values can be stiff or compliant.
virtual yarp::dev::ReturnValue isJointBraked(int j, bool &braked) const =0
Check is the joint brake is currently active.
virtual bool getLastJointFault(int j, int &fault, std::string &message)=0
virtual bool getMotorEncoders(double *encs)=0
Read the position of all motor encoders.
virtual bool getDutyCycle(int m, double *val)=0
Gets the current dutycycle of the output of the amplifier (i.e.
virtual bool setRefDutyCycle(int m, double ref)=0
Sets the reference dutycycle to a single motor.
virtual bool getRefDutyCycle(int m, double *ref)=0
Gets the last reference sent using the setRefDutyCycle function.
virtual bool getDutyCycles(double *vals)=0
Gets the current dutycycle of the output of the amplifier (i.e.
virtual bool setPid(const PidControlTypeEnum &pidtype, int j, const Pid &pid)=0
Set new pid value for a joint axis.
virtual bool getPid(const PidControlTypeEnum &pidtype, int j, Pid *pid)=0
Get current pid value for a specific joint.
virtual bool getAxes(int *ax)=0
Get the number of controlled axes.
virtual bool setRefSpeed(int j, double sp)=0
Set reference speed for a joint, this is the speed used during the interpolation of the trajectory.
virtual bool getTargetPosition(const int joint, double *ref)
Get the last position reference for the specified axis.
virtual bool setRefSpeeds(const double *spds)=0
Set reference speed on all joints.
virtual bool checkMotionDone(int j, bool *flag)=0
Check if the current trajectory is terminated.
virtual bool getRefSpeed(int j, double *ref)=0
Get reference speed for a joint.
virtual bool positionMove(int j, double ref)=0
Set new reference point for a single axis.
virtual bool setPosition(int j, double ref)=0
Set new position for a single axis.
virtual bool homingSingleJoint(int j)=0
homingSingleJoint: call the homing procedure for a single joint
virtual bool isCalibratorDevicePresent(bool *isCalib)
isCalibratorDevicePresent: check if a calibrator device has been set
virtual bool homingWholePart()=0
homingWholePart: call the homing procedure for a the whole part/device
virtual bool calibrateSingleJoint(int j)=0
calibrateSingleJoint: call the calibration procedure for the single joint
virtual bool calibrateWholePart()=0
calibrateWholePart: call the procedure for calibrating the whole device
virtual bool setRemoteVariable(std::string key, const yarp::os::Bottle &val)=0
virtual bool getRemoteVariable(std::string key, yarp::os::Bottle &val)=0
virtual bool getRemoteVariablesList(yarp::os::Bottle *listOfKeys)=0
virtual bool setRefTorque(int j, double t)=0
Set the reference value of the torque for a given joint.
virtual bool setMotorTorqueParams(int j, const yarp::dev::MotorTorqueParameters params)
Set a subset of motor parameters (bemf, ktau etc) useful for torque control.
virtual bool getMotorTorqueParams(int j, yarp::dev::MotorTorqueParameters *params)
Get a subset of motor parameters (bemf, ktau etc) useful for torque control.
virtual bool getTorques(double *t)=0
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
virtual bool getTorqueRange(int j, double *min, double *max)=0
Get the full scale of the torque sensor of a given joint.
virtual bool getRefTorque(int j, double *t)=0
Get the reference value of the torque for a given joint.
virtual bool setRefAcceleration(int j, double acc)=0
Set reference acceleration for a joint.
virtual bool getRefVelocity(const int joint, double *vel)
Get the last reference speed set by velocityMove for single joint.
virtual bool getRefAcceleration(int j, double *acc)=0
Get reference acceleration for a joint.
virtual bool velocityMove(int j, double sp)=0
Start motion at a given speed, single joint.
virtual yarp::dev::ReturnValue setDesiredVelocity(int jnt, double vel)=0
Set the velocity of single joint.
Contains the parameters for a PID.
A container for a device driver.
Definition PolyDriver.h:23
bool close() override
Close the DeviceDriver.
bool isValid() const
Check if device is valid.
bool open(const std::string &txt)
Construct and configure a device by its common name.
A simple collection of objects that can be described and transmitted in a portable way.
Definition Bottle.h:65
size_type size() const
Gets the number of elements in the bottle.
Definition Bottle.cpp:257
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition Bottle.cpp:252
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Definition Bottle.cpp:217
A mini-server for performing network communication in the background.
void close() override
Stop port activity.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Represents how to reach a part of a YARP network.
Definition Contact.h:33
bool write(const PortWriter &writer, const PortWriter *callback=nullptr) const override
Write an object to the port.
Definition Port.cpp:395
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
Definition Port.cpp:506
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition Port.cpp:79
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition Property.cpp:987
Helper class for finding config files and other external resources.
bool isNull() const override
Checks if the object is invalid.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition Stamp.cpp:124
static void delaySystem(double seconds)
virtual bool isString() const
Checks if value is a string.
Definition Value.cpp:156
virtual std::string asString() const
Get string value.
Definition Value.cpp:246
bool speedview_param_enabled
Definition main.cpp:35
bool debug_param_enabled
Definition main.cpp:34
bool enable_calib_all
Definition main.cpp:36
#define LOG_INFO(...)
Definition log.h:25
#define LOG_ERROR(...)
Definition log.h:19
@ VOCAB_PIDTYPE_TORQUE
Definition PidEnums.h:18
@ VOCAB_PIDTYPE_VELOCITY
Definition PidEnums.h:17
@ VOCAB_PIDTYPE_POSITION
Definition PidEnums.h:16
@ VOCAB_PIDTYPE_CURRENT
Definition PidEnums.h:19
@ VOCAB_JOINTTYPE_REVOLUTE
Definition IAxisInfo.h:24
#define MAX_WIDTH_JOINT
Definition partitem.h:37