RobotUnitModuleControlThread.cpp
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * ArmarX is free software; you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License version 2 as
6 * published by the Free Software Foundation.
7 *
8 * ArmarX is distributed in the hope that it will be useful, but
9 * WITHOUT ANY WARRANTY; without even the implied warranty of
10 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 * GNU General Public License for more details.
12 *
13 * You should have received a copy of the GNU General Public License
14 * along with this program. If not, see <http://www.gnu.org/licenses/>.
15 *
16 * @package RobotAPI::ArmarXObjects::RobotUnit
17 * @author Raphael Grimm ( raphael dot grimm at kit dot edu )
18 * @date 2018
19 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20 * GNU General Public License
21 */
22
24
25#include <SimoxUtility/math/convert/pos_rpy_to_mat4f.h>
26#include <VirtualRobot/VirtualRobotException.h>
27#include <VirtualRobot/XML/RobotIO.h>
28
33
45
47
49{
50 /**
51 * \brief This class allows minimal access to private members of \ref NJointControllerBase in a sane fashion for \ref ControlThread.
52 * \warning !! DO NOT ADD ANYTHING IF YOU DO NOT KNOW WAHT YOU ARE DOING! IF YOU DO SOMETHING WRONG YOU WILL CAUSE UNDEFINED BEHAVIOUR !!
53 */
55 {
56 friend class ControlThread;
57
58 static void
59 RtDeactivateController(const NJointControllerBasePtr& nJointCtrl)
60 {
61 nJointCtrl->rtDeactivateController();
62 }
63
64 static void
65 RtActivateController(const NJointControllerBasePtr& nJointCtrl)
66 {
67 nJointCtrl->rtActivateController();
68 }
69
70 static void
71 RtDeactivateControllerBecauseOfError(const NJointControllerBasePtr& nJointCtrl)
72 {
73 nJointCtrl->rtDeactivateControllerBecauseOfError();
74 }
75 };
76
77 /**
78 * \brief This class allows minimal access to private members of \ref ControlThreadDataBuffer in a sane fashion for \ref ControlThread.
79 * \warning !! DO NOT ADD ANYTHING IF YOU DO NOT KNOW WAHT YOU ARE DOING! IF YOU DO SOMETHING WRONG YOU WILL CAUSE UNDEFINED BEHAVIOUR !!
80 */
82 {
83 friend class ControlThread;
84
85 static std::vector<JointController*>&
86 GetActivatedJointControllers(ControlThread* p)
87 {
89 .controllersActivated.getWriteBuffer()
90 .jointControllers;
91 }
92
93 static std::vector<NJointControllerBase*>&
94 GetActivatedNJointControllers(ControlThread* p)
95 {
97 .controllersActivated.getWriteBuffer()
98 .nJointControllers;
99 }
100
101 static std::vector<std::size_t>&
102 GetActivatedJointToNJointControllerAssignement(ControlThread* p)
103 {
104 return p->_module<ControlThreadDataBuffer>()
105 .controllersActivated.getWriteBuffer()
106 .jointToNJointControllerAssignement;
107 }
108
109 static const std::vector<JointController*>&
110 GetActivatedJointControllers(const ControlThread* p)
111 {
112 return p->_module<ControlThreadDataBuffer>()
113 .controllersActivated.getWriteBuffer()
114 .jointControllers;
115 }
116
117 static const std::vector<NJointControllerBase*>&
118 GetActivatedNJointControllers(const ControlThread* p)
119 {
120 return p->_module<ControlThreadDataBuffer>()
121 .controllersActivated.getWriteBuffer()
122 .nJointControllers;
123 }
124
125 static const std::vector<std::size_t>&
126 GetActivatedJointToNJointControllerAssignement(const ControlThread* p)
127 {
128 return p->_module<ControlThreadDataBuffer>()
129 .controllersActivated.getWriteBuffer()
130 .jointToNJointControllerAssignement;
131 }
132
133 static void
134 AcceptRequestedJointToNJointControllerAssignement(ControlThread* p)
135 {
136 p->_module<ControlThreadDataBuffer>()
137 .controllersActivated.getWriteBuffer()
138 .jointToNJointControllerAssignement = p->_module<ControlThreadDataBuffer>()
139 .controllersRequested.getReadBuffer()
140 .jointToNJointControllerAssignement;
141 }
142
143 static void
144 CommitActivatedControllers(ControlThread* p)
145 {
146 return p->_module<ControlThreadDataBuffer>().controllersActivated.commitWrite();
147 }
148
149 static void
150 ResetActivatedControllerAssignement(ControlThread* p)
151 {
152 return p->_module<ControlThreadDataBuffer>()
153 .controllersActivated.getWriteBuffer()
154 .resetAssignement();
155 }
156
157 static const std::vector<JointController*>&
158 GetRequestedJointControllers(const ControlThread* p)
159 {
160 //do NOT update here!
161 return p->_module<ControlThreadDataBuffer>()
162 .controllersRequested.getReadBuffer()
163 .jointControllers;
164 }
165
166 static const std::vector<NJointControllerBase*>&
167 GetRequestedNJointControllers(const ControlThread* p)
168 {
169 //do NOT update here!
170 return p->_module<ControlThreadDataBuffer>()
171 .controllersRequested.getReadBuffer()
172 .nJointControllers;
173 }
174
175 static const std::vector<std::size_t>&
176 GetRequestedJointToNJointControllerAssignement(const ControlThread* p)
177 {
178 //do NOT update here!
179 return p->_module<ControlThreadDataBuffer>()
180 .controllersRequested.getReadBuffer()
181 .jointToNJointControllerAssignement;
182 }
183
184 static bool
185 RequestedControllersChanged(const ControlThread* p)
186 {
187 //only place allowed to update this buffer!
188 return p->_module<ControlThreadDataBuffer>().controllersRequested.updateReadBuffer();
189 }
190
191 /// Activate a joint controller from the rt loop (only works in switch mode RTThread)
192 static void
193 RTSetJointController(ControlThread* p, JointController* c, std::size_t index)
194 {
196 //do NOT update here!
197 auto& readbuf =
198 p->_module<ControlThreadDataBuffer>().controllersRequested._getNonConstReadBuffer();
199 auto& j = readbuf.jointControllers;
200 auto& assig = readbuf.jointToNJointControllerAssignement;
201 auto& nj = readbuf.nJointControllers;
202 ARMARX_CHECK_LESS(index, j.size());
203 const auto assigNJ = assig.at(index);
205 {
206 //an NJointController is activated! Deactivate it and reset all joit devs
207 nj.at(assigNJ) = nullptr;
208 for (std::size_t i = 0; i < assig.size(); ++i)
209 {
210 if (assig.at(i) == assigNJ)
211 {
212 j.at(i) = j.at(i)->rtGetParent().rtGetJointStopMovementController();
213 }
214 }
215 }
216 j.at(index) = c;
217 }
218 };
219
220 /**
221 * \brief This class allows minimal access to private members of \ref Devices in a sane fashion for \ref ControlThread.
222 * \warning !! DO NOT ADD ANYTHING IF YOU DO NOT KNOW WAHT YOU ARE DOING! IF YOU DO SOMETHING WRONG YOU WILL CAUSE UNDEFINED BEHAVIOUR !!
223 */
225 {
226 friend class ControlThread;
227
228 static const std::vector<ControlDevicePtr>&
229 GetControlDevices(const ControlThread* p)
230 {
231 return p->_module<Devices>().controlDevices.values();
232 }
233
234 static const std::vector<SensorDevicePtr>&
235 GetSensorDevices(const ControlThread* p)
236 {
237 return p->_module<Devices>().sensorDevices.values();
238 }
239
240 static const std::vector<const SensorValueBase*>&
241 GetSensorValues(const ControlThread* p)
242 {
243 return p->_module<Devices>().sensorValues;
244 }
245
246 static const std::vector<std::vector<PropagateConst<ControlTargetBase*>>>&
247 GetControlTargets(const ControlThread* p)
248 {
249 return p->_module<Devices>().controlTargets;
250 }
251
252 static RTThreadTimingsSensorDevice&
253 GetThreadTimingsSensorDevice(const ControlThread* p)
254 {
255 return *(p->_module<Devices>().rtThreadTimingsSensorDevice);
256 }
257
258 static void
259 UpdateRobotWithSensorValues(const ControlThread* p,
260 const VirtualRobot::RobotPtr& robot,
261 const std::vector<VirtualRobot::RobotNodePtr>& robotNodes)
262 {
263 p->_module<Devices>().updateVirtualRobotFromSensorValues(
264 robot, robotNodes, p->_module<Devices>().sensorValues);
265 }
266 };
267
268 /**
269 * \brief This class allows minimal access to private members of \ref Devices in a sane fashion for \ref ControlThread.
270 * \warning !! DO NOT ADD ANYTHING IF YOU DO NOT KNOW WAHT YOU ARE DOING! IF YOU DO SOMETHING WRONG YOU WILL CAUSE UNDEFINED BEHAVIOUR !!
271 */
273 {
274 friend class ControlThread;
275
276 static bool
277 HeartbeatMissing(const ControlThread* p)
278 {
279 const Management& m = p->_module<Management>();
280 long now = TimeUtil::GetTime(true).toMilliSeconds();
281 if (!m.heartbeatRequired || now < m.controlLoopStartTime + m.heartbeatStartupMarginMS)
282 {
283 return false;
284 }
285 return (now - m.lastHeartbeat) > m.heartbeatMaxCycleMS;
286 }
287 };
288} // namespace armarx::RobotUnitModule
289
291{
292 bool
294 {
297 {
299 };
300
301 //store controllers activated before switching controllers
302 {
303 preSwitchSetup_ActivatedJointControllers = rtGetActivatedJointControllers();
304 preSwitchSetup_ActivatedJointToNJointControllerAssignement =
305 rtGetActivatedJointToNJointControllerAssignement();
306 preSwitchSetup_ActivatedNJointControllers = rtGetActivatedNJointControllers();
307 }
308
310 {
311 const auto& actJC = rtGetActivatedJointControllers();
312 const auto& assig = rtGetActivatedJointToNJointControllerAssignement();
313 const auto& actNJC = rtGetActivatedNJointControllers();
314
315 //store controllers activated after switching controllers
316 {
317 postSwitchSetup_ActivatedJointControllers = actJC;
318 postSwitchSetup_ActivatedJointToNJointControllerAssignement = assig;
319 postSwitchSetup_ActivatedNJointControllers = actNJC;
320 }
321
322 std::size_t numSyncNj = 0;
323 std::size_t numAsyncNj = 0;
324
325 for (std::size_t i = 0; i < actJC.size(); ++i)
326 {
327 if (actNJC.at(i) == nullptr)
328 {
329 continue;
330 }
331 if (dynamic_cast<SynchronousNJointController*>(actNJC.at(i)))
332 {
333 _activatedSynchronousNJointControllersIdx.at(numSyncNj++) = i;
334 }
335 else if (dynamic_cast<AsynchronousNJointController*>(actNJC.at(i)))
336 {
337 _activatedAsynchronousNJointControllersIdx.at(numAsyncNj++) = i;
338 }
339 else
340 {
342 "NJoint controller that is neither SynchronousNJointController"
343 " nor AsynchronousNJointController: %s",
344 actNJC.at(i)->rtGetClassName().c_str());
345 // Throwing exceptions in a destructor causes std::abort to be called
346 //throw std::logic_error{};
347 }
348 }
349 for (std::size_t i = numSyncNj;
350 i < _maxControllerCount &&
351 _activatedSynchronousNJointControllersIdx.at(i) != _maxControllerCount;
352 ++i)
353 {
354 _activatedSynchronousNJointControllersIdx.at(i) = _maxControllerCount;
355 }
356 for (std::size_t i = numAsyncNj;
357 i < _maxControllerCount &&
358 _activatedAsynchronousNJointControllersIdx.at(i) != _maxControllerCount;
359 ++i)
360 {
361 _activatedAsynchronousNJointControllersIdx.at(i) = _maxControllerCount;
362 }
363 };
364
365
366 rtSwitchControllerSetupChangedControllers = false;
367
368 // a missing heartbeat (if required by the config) is interpreted as emergencyStop == true
369 if (!emergencyStop && ManagementAttorneyForControlThread::HeartbeatMissing(this))
370 {
371 rtSetEmergencyStopState(EmergencyStopState::eEmergencyStopActive);
372 ARMARX_RT_LOGF_ERROR("Emergency Stop was activated because heartbeat is missing!")
373 .deactivateSpam(1);
374 }
375
376 const bool rtThreadOverridesControl = mode != SwitchControllerMode::IceRequests;
377 // mode == RTThread -> control flow in hand of rt thread (ignoring estop)
378 // !emergencyStop && !rtIsInEmergencyStop() -> normal control flow
379 // !emergencyStop && rtIsInEmergencyStop() -> force switch to reactivate old ( + reset flag)
380 // emergencyStop && !rtIsInEmergencyStop() -> deactivate all + set flag
381 // emergencyStop && rtIsInEmergencyStop() -> nothing to do
382 if (emergencyStop && !rtThreadOverridesControl)
383 {
385 {
386 return false;
387 }
388 rtIsInEmergencyStop_ = true;
389 //deactivate all nJointCtrl
390 for (auto& nJointCtrl : rtGetActivatedNJointControllers())
391 {
392 if (nJointCtrl)
393 {
394 NJointControllerAttorneyForControlThread::RtDeactivateController(nJointCtrl);
395 nJointCtrl = nullptr;
396 rtSwitchControllerSetupChangedControllers = true;
397 }
398 }
399 //set all JointCtrl to emergency stop (except stop movement)
400 for (std::size_t i = 0; i < rtGetControlDevices().size(); ++i)
401 {
402 const ControlDevicePtr& controlDevice = rtGetControlDevices().at(i);
403 const auto active = controlDevice->rtGetActiveJointController();
404 const auto stopMov = controlDevice->rtGetJointStopMovementController();
405 const auto emergency = controlDevice->rtGetJointEmergencyStopController();
406 if (active != stopMov && active != emergency)
407 {
408 controlDevice->rtSetActiveJointController(emergency);
409 rtGetActivatedJointControllers().at(i) = emergency;
410 rtSwitchControllerSetupChangedControllers = true;
411 }
412 }
413 if (rtSwitchControllerSetupChangedControllers)
414 {
415 ControlThreadDataBufferAttorneyForControlThread::
416 ResetActivatedControllerAssignement(this);
417 // the activated controllers are committed in rtUpdateSensorAndControlBuffer(...)
418 }
419 return rtSwitchControllerSetupChangedControllers;
420 }
421
422 if (!rtThreadOverridesControl &&
423 !ControlThreadDataBufferAttorneyForControlThread::RequestedControllersChanged(this) &&
425 {
426 return false;
427 }
428 rtIsInEmergencyStop_ = false;
429
430 //handle nJointCtrl
431 {
432 const auto& allReqNJ = rtGetRequestedNJointControllers();
433 auto& allActdNJ = rtGetActivatedNJointControllers();
434 //"merge"
435 std::size_t n = rtGetControlDevices().size();
436 std::size_t idxAct = 0;
437 std::size_t idxReq = 0;
438 for (std::size_t i = 0; i < 2 * n; ++i)
439 {
440 //skip nullptrs in act
441 while (idxAct < n && !allActdNJ.at(idxAct))
442 {
443 ++idxAct;
444 }
445 const NJointControllerBasePtr& req =
446 idxReq < n ? allReqNJ.at(idxReq) : nullptr; //may be null
447 const NJointControllerBasePtr& act =
448 idxAct < n ? allActdNJ.at(idxAct) : nullptr; //may be null if it is the last
449 const auto reqId = reinterpret_cast<std::uintptr_t>(req.get());
450 const auto actId = reinterpret_cast<std::uintptr_t>(act.get());
451
452 if (reqId > actId)
453 {
454 //new ctrl
455 rtSyncNJointControllerRobot(req.get());
456 NJointControllerAttorneyForControlThread::RtActivateController(req);
457 ++idxReq;
458 rtSwitchControllerSetupChangedControllers = true;
459 }
460 else if (reqId < actId)
461 {
462 NJointControllerAttorneyForControlThread::RtDeactivateController(act);
463 rtSwitchControllerSetupChangedControllers = true;
464 ++idxAct;
465 }
466 else //if(reqId == actId)
467 {
468 //same ctrl or both null ctrl
469 ++idxReq;
470 ++idxAct;
471 }
472 if (idxAct >= n && !req)
473 {
474 break;
475 }
476 }
477 allActdNJ = allReqNJ;
478 }
479
480 //handle Joint Ctrl
481 {
482 const auto& allReqJ = rtGetRequestedJointControllers();
483 auto& allActdJ = rtGetActivatedJointControllers();
484 ARMARX_CHECK_EQUAL(allReqJ.size(), rtGetControlDevices().size());
485 for (std::size_t i = 0; i < rtGetControlDevices().size(); ++i)
486 {
487 auto& controlDevice = rtGetControlDevices().at(i);
488 const auto requestedJointCtrl = allReqJ.at(i);
489 controlDevice->rtSetActiveJointController(requestedJointCtrl);
490 allActdJ.at(i) = requestedJointCtrl;
491 }
492 }
493 ControlThreadDataBufferAttorneyForControlThread::
494 AcceptRequestedJointToNJointControllerAssignement(this);
495 // the activated controllers are committed in rtUpdateSensorAndControlBuffer(...)
496 return true;
497 }
498
499 void
501 {
503 for (const ControlDevicePtr& controlDev : rtGetControlDevices())
504 {
505 controlDev->rtGetActiveJointController()->rtResetTarget();
506 }
508 }
509
510 void
512 {
514 numberOfInvalidTargetsInThisIteration = 0;
515 const auto& cdevs = rtGetControlDevices();
516 for (std::size_t i = 0; i < cdevs.size(); ++i)
517 {
518 if (!rtGetActivatedJointControllers().at(i)->rtIsTargetValid())
519 {
520 ARMARX_RT_LOGF_ERROR("INVALID TARGET for JointController (idx = %lu) '%s'",
521 i,
522 cdevs.at(i)->rtGetDeviceName());
523 ARMARX_ERROR << ">>>INVALID TARGET for JointController (idx = " << i << ") '"
524 << cdevs.at(i)->getDeviceName() << "'";
526 ++numberOfInvalidTargetsInThisIteration;
527 }
528 }
529 // the activated controllers are committed in rtUpdateSensorAndControlBuffer(...)
531 }
532
533 void
534 ControlThread::rtReadSensorDeviceValues(const IceUtil::Time& sensorValuesTimestamp,
535 const IceUtil::Time& timeSinceLastIteration)
536 {
538 for (const SensorDevicePtr& device : rtGetSensorDevices())
539 {
540 if (device)
541 {
542 device->rtReadSensorValues(sensorValuesTimestamp, timeSinceLastIteration);
543 }
544 else
545 {
546 ARMARX_RT_LOGF_ERROR("Device is null!");
547 }
548 }
549 DevicesAttorneyForControlThread::UpdateRobotWithSensorValues(this, rtRobot, rtRobotNodes);
550 rtPostReadSensorDeviceValues(sensorValuesTimestamp, timeSinceLastIteration);
552 }
553
554 void
555 ControlThread::rtPostReadSensorDeviceValues(const IceUtil::Time& sensorValuesTimestamp,
556 const IceUtil::Time& timeSinceLastIteration)
557 {
558 if (dynamicsHelpers)
559 {
560 // auto start = IceUtil::Time::now();
561 dynamicsHelpers->update(sensorValuesTimestamp, timeSinceLastIteration);
562 // auto end = IceUtil::Time::now();
563 // ARMARX_INFO << "Dynamics duration: " << (end-start).toMicroSeconds();
564 }
565 }
566
567 void
568 ControlThread::rtRunJointControllers(const IceUtil::Time& sensorValuesTimestamp,
569 const IceUtil::Time& timeSinceLastIteration)
570 {
572 for (const ControlDevicePtr& device : rtGetControlDevices())
573 {
574 device->rtRun(sensorValuesTimestamp, timeSinceLastIteration);
575 }
577 }
578
579 void
580 ControlThread::rtRunNJointControllers(const IceUtil::Time& sensorValuesTimestamp,
581 const IceUtil::Time& timeSinceLastIteration)
582 {
584 // bool activeControllersChanged = false;
585 auto activatedNjointCtrls = rtGetActivatedNJointControllers();
586 //start async
587 for (std::size_t nJointCtrlIndex : _activatedAsynchronousNJointControllersIdx)
588 {
589 if (nJointCtrlIndex == _maxControllerCount)
590 {
591 break;
592 }
593 auto nJointCtrl = static_cast<AsynchronousNJointController*>(
594 activatedNjointCtrls.at(nJointCtrlIndex));
595 if (!nJointCtrl)
596 {
597 continue;
598 }
599 try
600 {
601 if (nJointCtrl->rtGetErrorState())
602 {
604 "NJointControllerBase '%s' requested deactivation while activating it",
605 nJointCtrl->rtGetInstanceName().c_str());
607 }
608 auto start = TimeUtil::GetTime(true);
609 rtSyncNJointControllerRobot(nJointCtrl);
610 nJointCtrl->rtRunIterationBegin(sensorValuesTimestamp, timeSinceLastIteration);
611 auto duration = TimeUtil::GetTime(true) - start;
612 if (nJointCtrl->rtGetErrorState())
613 {
615 "NJointControllerBase '%s' requested deactivation while running it",
616 nJointCtrl->rtGetInstanceName().c_str());
618 }
619 if (static_cast<std::size_t>(duration.toMicroSeconds()) >
620 nJointCtrl->rtGetNumberOfUsedControlDevices() * usPerDevUntilError)
621 {
622 ARMARX_RT_LOGF_ERROR("The NJointControllerBase '%s' took %ld µs to run!",
623 nJointCtrl->rtGetInstanceName().c_str(),
624 duration.toMicroSeconds())
625 .deactivateSpam(5);
626 }
627 else if (static_cast<std::size_t>(duration.toMicroSeconds()) >
628 nJointCtrl->rtGetNumberOfUsedControlDevices() * usPerDevUntilWarn)
629 {
630 ARMARX_RT_LOGF_WARNING("The NJointControllerBase '%s' took %ld µs to run!",
631 nJointCtrl->rtGetInstanceName().c_str(),
632 duration.toMicroSeconds())
633 .deactivateSpam(5);
634 }
635 }
636 catch (...)
637 {
638 ARMARX_ERROR << "NJoint Controller " << nJointCtrl->getInstanceName()
639 << " threw an exception and is now deactivated: "
642 }
643 }
644
645 //start sync
646 for (std::size_t nJointCtrlIndex : _activatedSynchronousNJointControllersIdx)
647 {
648 if (nJointCtrlIndex == _maxControllerCount)
649 {
650 break;
651 }
652 auto nJointCtrl =
653 static_cast<SynchronousNJointController*>(activatedNjointCtrls.at(nJointCtrlIndex));
654 try
655 {
656 if (nJointCtrl)
657 {
658 if (nJointCtrl->rtGetErrorState())
659 {
661 "NJointControllerBase '%s' requested deactivation while activating it",
662 nJointCtrl->rtGetInstanceName().c_str());
664 // activeControllersChanged = true;
665 }
666
667 auto start = TimeUtil::GetTime(true);
668 rtSyncNJointControllerRobot(nJointCtrl);
669 nJointCtrl->rtSwapBufferAndRun(sensorValuesTimestamp, timeSinceLastIteration);
670 auto duration = TimeUtil::GetTime(true) - start;
671 if (nJointCtrl->rtGetErrorState())
672 {
674 "NJointControllerBase '%s' requested deactivation while running it",
675 nJointCtrl->rtGetInstanceName().c_str());
677 // activeControllersChanged = true;
678 }
679 if (static_cast<std::size_t>(duration.toMicroSeconds()) >
680 nJointCtrl->rtGetNumberOfUsedControlDevices() * usPerDevUntilError)
681 {
682 ARMARX_RT_LOGF_ERROR("The NJointControllerBase '%s' took %ld µs to run!",
683 nJointCtrl->rtGetInstanceName().c_str(),
684 duration.toMicroSeconds())
685 .deactivateSpam(5);
686 }
687 else if (static_cast<std::size_t>(duration.toMicroSeconds()) >
688 nJointCtrl->rtGetNumberOfUsedControlDevices() * usPerDevUntilWarn)
689 {
690 ARMARX_RT_LOGF_WARNING("The NJointControllerBase '%s' took %ld µs to run!",
691 nJointCtrl->rtGetInstanceName().c_str(),
692 duration.toMicroSeconds())
693 .deactivateSpam(5);
694 }
695 }
696 }
697 catch (...)
698 {
699 ARMARX_ERROR << "NJoint Controller " << nJointCtrl->getInstanceName()
700 << " threw an exception and is now deactivated: "
703 // activeControllersChanged = true;
704 }
705 }
706 //stop async
707 for (std::size_t nJointCtrlIndex : _activatedAsynchronousNJointControllersIdx)
708 {
709 if (nJointCtrlIndex == _maxControllerCount)
710 {
711 break;
712 }
713 auto nJointCtrl = static_cast<AsynchronousNJointController*>(
714 activatedNjointCtrls.at(nJointCtrlIndex));
715 if (!nJointCtrl)
716 {
717 continue;
718 }
719 try
720 {
721 if (nJointCtrl->rtGetErrorState())
722 {
724 "NJointControllerBase '%s' requested deactivation while activating it",
725 nJointCtrl->rtGetInstanceName().c_str());
727 }
728 auto start = TimeUtil::GetTime(true);
729 rtSyncNJointControllerRobot(nJointCtrl);
730 nJointCtrl->rtRunIterationEnd(sensorValuesTimestamp, timeSinceLastIteration);
731 auto duration = TimeUtil::GetTime(true) - start;
732 if (nJointCtrl->rtGetErrorState())
733 {
735 "NJointControllerBase '%s' requested deactivation while running it",
736 nJointCtrl->rtGetInstanceName().c_str());
738 }
739 if (static_cast<std::size_t>(duration.toMicroSeconds()) >
740 nJointCtrl->rtGetNumberOfUsedControlDevices() * usPerDevUntilError)
741 {
742 ARMARX_RT_LOGF_ERROR("The NJointControllerBase '%s' took %ld µs to run!",
743 nJointCtrl->rtGetInstanceName().c_str(),
744 duration.toMicroSeconds())
745 .deactivateSpam(5);
746 }
747 else if (static_cast<std::size_t>(duration.toMicroSeconds()) >
748 nJointCtrl->rtGetNumberOfUsedControlDevices() * usPerDevUntilWarn)
749 {
750 ARMARX_RT_LOGF_WARNING("The NJointControllerBase '%s' took %ld µs to run!",
751 nJointCtrl->rtGetInstanceName().c_str(),
752 duration.toMicroSeconds())
753 .deactivateSpam(5);
754 }
755 }
756 catch (...)
757 {
758 ARMARX_ERROR << "NJoint Controller " << nJointCtrl->getInstanceName()
759 << " threw an exception and is now deactivated: "
762 }
763 }
764 // the activated controllers are committed in rtUpdateSensorAndControlBuffer(...)
766 }
767
768 void
770 {
771 const NJointControllerBasePtr& nJointCtrl =
772 rtGetActivatedNJointControllers().at(nJointCtrlIndex);
773 NJointControllerAttorneyForControlThread::RtDeactivateControllerBecauseOfError(nJointCtrl);
774 for (auto ctrlDevIdx : nJointCtrl->rtGetControlDeviceUsedIndices())
775 {
776 const ControlDevicePtr& controlDevice = rtGetControlDevices().at(ctrlDevIdx);
777 JointController* es = controlDevice->rtGetJointEmergencyStopController();
778
779 ARMARX_CHECK_EQUAL(rtGetActivatedJointToNJointControllerAssignement().at(ctrlDevIdx),
780 nJointCtrlIndex)
781 << VAROUT(ctrlDevIdx) << "\n"
782 << VAROUT(controlDevice->getDeviceName()) << "\n"
783 << dumpRtState();
784
785 controlDevice->rtSetActiveJointController(es);
786 rtGetActivatedJointControllers().at(ctrlDevIdx) = es;
787 rtGetActivatedJointToNJointControllerAssignement().at(ctrlDevIdx) = IndexSentinel();
788 }
789 rtGetActivatedNJointControllers().at(nJointCtrlIndex) = nullptr;
790 //check ControlDeviceHardwareControlModeGroups
791 {
792 for (auto ctrlDevIdx : nJointCtrl->rtGetControlDeviceUsedIndices())
793 {
794 const auto& ctrlModeGroups = _module<Devices>().getControlModeGroups();
795 const auto groupIdx = ctrlModeGroups.groupIndices.at(ctrlDevIdx);
796 if (groupIdx == IndexSentinel())
797 {
798 continue;
799 }
800 ControlDevice* const dev = rtGetControlDevices().at(ctrlDevIdx).get();
801 JointController* const jointCtrl = dev->rtGetActiveJointController();
802 const auto hwModeHash = jointCtrl->rtGetHardwareControlModeHash();
803 //this device is in a group!
804 // -> check all other devices
805 for (const auto otherIdx : ctrlModeGroups.deviceIndices.at(groupIdx))
806 {
807 ControlDevice* const otherDev = rtGetControlDevices().at(otherIdx).get();
808 JointController* const otherJointCtrl = otherDev->rtGetActiveJointController();
809 const auto otherHwModeHash = otherJointCtrl->rtGetHardwareControlModeHash();
810 if (hwModeHash == otherHwModeHash)
811 {
812 //the assigend ctrl has the same hwMode -> don't do anything
813 continue;
814 }
815 const auto otherNJointCtrl1Idx =
816 rtGetActivatedJointToNJointControllerAssignement().at(otherIdx);
817 if (otherNJointCtrl1Idx == IndexSentinel())
818 {
819 //the hwmodes are different! (hence the other ctrl must be in stop movement
820 ARMARX_CHECK_EXPRESSION(otherJointCtrl ==
822 //we need to activate the es contoller
824 otherDev->rtSetActiveJointController(es);
826 rtGetActivatedJointControllers().at(otherIdx) = es;
827 continue;
828 }
829 //the devs NJoint controller needs to be deactivated
831 }
832 }
833 }
835 }
836
837 void
839 {
840 std::size_t nJointCtrlIndex =
841 rtGetActivatedJointToNJointControllerAssignement().at(ctrlDevIndex);
842 ARMARX_CHECK_LESS(nJointCtrlIndex, rtGetControlDevices().size())
843 << "no NJoint controller controls this device (name = "
844 << rtGetControlDevices().at(ctrlDevIndex)->getDeviceName() << ", ControlMode = "
845 << rtGetActivatedJointControllers().at(ctrlDevIndex)->getControlMode() << ")!"
846 << "\n"
847 << "This means an invariant is violated! Dumping data for debugging:\n"
848 << VAROUT(ctrlDevIndex) << "\n"
849 << dumpRtState();
850
852 }
853
854 void
855 ControlThread::rtUpdateSensorAndControlBuffer(const IceUtil::Time& sensorValuesTimestamp,
856 const IceUtil::Time& timeSinceLastIteration)
857 {
859 //commit all changes to activated controllers (joint, njoint, assignement)
860 {
861 ControlThreadDataBufferAttorneyForControlThread::CommitActivatedControllers(this);
862 }
863
864 SensorAndControl& sc = _module<ControlThreadDataBuffer>().rtGetSensorAndControlBuffer();
865 sc.writeTimestamp = armarx::rtNow(); // this has to be in real time
866 sc.sensorValuesTimestamp = sensorValuesTimestamp;
867 sc.timeSinceLastIteration = timeSinceLastIteration;
868 ARMARX_CHECK_EQUAL(rtGetSensorDevices().size(), sc.sensors.size());
869 for (std::size_t sensIdx = 0; sensIdx < rtGetSensorDevices().size(); ++sensIdx)
870 {
871 rtGetSensorDevices().at(sensIdx)->getSensorValue()->_copyTo(sc.sensors.at(sensIdx));
872 }
873
875 for (std::size_t ctrlIdx = 0; ctrlIdx < rtGetControlDevices().size(); ++ctrlIdx)
876 {
877 ControlDevice& controlDevice = *rtGetControlDevices().at(ctrlIdx);
878 ARMARX_CHECK_EQUAL(controlDevice.rtGetJointControllers().size(),
879 sc.control.at(ctrlIdx).size());
880 for (std::size_t targIdx = 0; targIdx < controlDevice.rtGetJointControllers().size();
881 ++targIdx)
882 {
883 JointController& jointCtrl = *controlDevice.rtGetJointControllers().at(targIdx);
884 jointCtrl.getControlTarget()->_copyTo(sc.control.at(ctrlIdx).at(targIdx));
885 }
886 }
887 _module<ControlThreadDataBuffer>().rtSensorAndControlBufferCommitWrite();
888
889
891 }
892
893 const std::vector<ControlDevicePtr>&
895 {
896 return DevicesAttorneyForControlThread::GetControlDevices(this);
897 }
898
899 const std::vector<SensorDevicePtr>&
901 {
902 return DevicesAttorneyForControlThread::GetSensorDevices(this);
903 }
904
907 {
908 return DevicesAttorneyForControlThread::GetThreadTimingsSensorDevice(this);
909 }
910
911 void
913 {
914 if (state == EmergencyStopState::eEmergencyStopActive)
915 {
916 emergencyStopStateRequest = EmergencyStopStateRequest::RequestActive;
917 }
918 else
919 {
920 emergencyStopStateRequest = EmergencyStopStateRequest::RequestInactive;
921 }
922 }
923
924 void
925 ControlThread::_preFinishControlThreadInitialization()
926 {
927 throwIfInControlThread(BOOST_CURRENT_FUNCTION);
928 controlThreadId = std::this_thread::get_id();
929
930 _maxControllerCount = rtGetActivatedJointControllers().size();
931
932 ARMARX_CHECK_EQUAL(_maxControllerCount,
933 rtGetActivatedJointToNJointControllerAssignement().size());
934 ARMARX_CHECK_EQUAL(_maxControllerCount, rtGetActivatedNJointControllers().size());
935 //resize buffers used for error oputput
936 preSwitchSetup_ActivatedJointControllers.resize(_maxControllerCount);
937 postSwitchSetup_ActivatedJointControllers.resize(_maxControllerCount);
938
939 preSwitchSetup_ActivatedJointToNJointControllerAssignement.resize(_maxControllerCount);
940 postSwitchSetup_ActivatedJointToNJointControllerAssignement.resize(_maxControllerCount);
941
942 preSwitchSetup_ActivatedNJointControllers.resize(_maxControllerCount);
943 postSwitchSetup_ActivatedNJointControllers.resize(_maxControllerCount);
944
945 _activatedSynchronousNJointControllersIdx.resize(_maxControllerCount, _maxControllerCount);
946 _activatedAsynchronousNJointControllersIdx.resize(_maxControllerCount, _maxControllerCount);
947
948 // setup inverse dynamics
949 if (getProperty<bool>("EnableInverseDynamics").getValue())
950 {
951 RobotUnit* robotUnit = dynamic_cast<RobotUnit*>(this);
952 ARMARX_CHECK_EXPRESSION(robotUnit);
953 std::shared_ptr<DynamicsHelper> dynamicsHelpers(new DynamicsHelper(robotUnit));
954 auto bodySetName = getProperty<std::string>("InverseDynamicsRobotBodySet").getValue();
955 auto rtRobotBodySet = rtGetRobot()->getRobotNodeSet(bodySetName);
956 ARMARX_CHECK_EXPRESSION(rtRobotBodySet)
957 << "could not find robot node set with name: " << bodySetName
958 << " - Check property InverseDynamicsRobotBodySet";
959 // rtfilters::RTFilterBasePtr accFilter(new rtfilters::ButterworthFilter(100, 1000, Lowpass, 1));
960 // rtfilters::RTFilterBasePtr velFilter(new rtfilters::ButterworthFilter(100, 1000, Lowpass, 1));
963
964 auto setList =
965 armarx::Split(getProperty<std::string>("InverseDynamicsRobotJointSets").getValue(),
966 ",",
967 true,
968 true);
969 for (auto& set : setList)
970 {
971 auto rns = rtGetRobot()->getRobotNodeSet(set);
972 ARMARX_CHECK_EXPRESSION(rns) << "could not find robot node set with name: " << set
973 << " - Check property InverseDynamicsRobotJointSets";
974 dynamicsHelpers->addRobotPart(rns, rtRobotBodySet, velFilter, accFilter);
975 ARMARX_VERBOSE << "Added nodeset " << set << " for inverse dynamics";
976 }
977
978 this->dynamicsHelpers = dynamicsHelpers;
979 }
980 }
981
982 void
983 ControlThread::_preOnInitRobotUnit()
984 {
985 throwIfInControlThread(BOOST_CURRENT_FUNCTION);
986 try
987 {
988 rtRobot = VirtualRobot::RobotIO::loadRobot(_module<RobotData>().getRobotFileName(),
989 VirtualRobot::RobotIO::eStructure);
990 rtRobot->setUpdateCollisionModel(false);
991 rtRobot->setUpdateVisualization(false);
992 rtRobot->setThreadsafe(false);
993 rtRobotNodes = rtRobot->getRobotNodes();
994 }
995 catch (VirtualRobot::VirtualRobotException& e)
996 {
997 throw UserException(e.what());
998 }
999 usPerDevUntilWarn = getProperty<std::size_t>(
1000 "NjointController_AllowedExecutionTimePerControlDeviceUntilWarning")
1001 .getValue();
1002 usPerDevUntilError = getProperty<std::size_t>(
1003 "NjointController_AllowedExecutionTimePerControlDeviceUntilError")
1004 .getValue();
1005 }
1006
1007 void
1009 {
1010 throwIfInControlThread(BOOST_CURRENT_FUNCTION);
1011 _module<Units>().getEmergencyStopMaster()->setEmergencyStopState(state);
1012 }
1013
1014 EmergencyStopState
1016 {
1017 throwIfInControlThread(BOOST_CURRENT_FUNCTION);
1018 return emergencyStop ? EmergencyStopState::eEmergencyStopActive
1019 : EmergencyStopState::eEmergencyStopInactive;
1020 }
1021
1022 EmergencyStopState
1024 {
1025 throwIfInControlThread(BOOST_CURRENT_FUNCTION);
1026 return rtIsInEmergencyStop() ? EmergencyStopState::eEmergencyStopActive
1027 : EmergencyStopState::eEmergencyStopInactive;
1028 }
1029
1030 void
1031 ControlThread::setEmergencyStopStateNoReportToTopic(EmergencyStopState state)
1032 {
1033 throwIfInControlThread(BOOST_CURRENT_FUNCTION);
1034 emergencyStop = (state == EmergencyStopState::eEmergencyStopActive);
1035 }
1036
1037 void
1038 ControlThread::processEmergencyStopRequest()
1039 {
1040 const auto state =
1041 emergencyStopStateRequest.exchange(EmergencyStopStateRequest::RequestNone);
1042 switch (state)
1043 {
1044 case EmergencyStopStateRequest::RequestActive:
1045 setEmergencyStopState(EmergencyStopState::eEmergencyStopActive);
1046 break;
1047 case EmergencyStopStateRequest::RequestInactive:
1048 setEmergencyStopState(EmergencyStopState::eEmergencyStopInactive);
1049 break;
1050 case EmergencyStopStateRequest::RequestNone:
1051 break;
1052 default:
1053 ARMARX_CHECK_EXPRESSION(!static_cast<int>(state))
1054 << "Unkown value for EmergencyStopStateRequest";
1055 }
1056 }
1057
1058 const std::vector<JointController*>&
1059 ControlThread::rtGetActivatedJointControllers() const
1060 {
1061 return ControlThreadDataBufferAttorneyForControlThread::GetActivatedJointControllers(this);
1062 }
1063
1064 const std::vector<NJointControllerBase*>&
1065 ControlThread::rtGetActivatedNJointControllers() const
1066 {
1067 return ControlThreadDataBufferAttorneyForControlThread::GetActivatedNJointControllers(this);
1068 }
1069
1070 const std::vector<std::size_t>&
1071 ControlThread::rtGetActivatedJointToNJointControllerAssignement() const
1072 {
1073 return ControlThreadDataBufferAttorneyForControlThread::
1074 GetActivatedJointToNJointControllerAssignement(this);
1075 }
1076
1077 std::vector<JointController*>&
1078 ControlThread::rtGetActivatedJointControllers()
1079 {
1080 return ControlThreadDataBufferAttorneyForControlThread::GetActivatedJointControllers(this);
1081 }
1082
1083 std::vector<NJointControllerBase*>&
1084 ControlThread::rtGetActivatedNJointControllers()
1085 {
1086 return ControlThreadDataBufferAttorneyForControlThread::GetActivatedNJointControllers(this);
1087 }
1088
1089 std::vector<std::size_t>&
1090 ControlThread::rtGetActivatedJointToNJointControllerAssignement()
1091 {
1092 return ControlThreadDataBufferAttorneyForControlThread::
1093 GetActivatedJointToNJointControllerAssignement(this);
1094 }
1095
1096 const std::vector<JointController*>&
1097 ControlThread::rtGetRequestedJointControllers() const
1098 {
1099 return ControlThreadDataBufferAttorneyForControlThread::GetRequestedJointControllers(this);
1100 }
1101
1102 const std::vector<NJointControllerBase*>&
1103 ControlThread::rtGetRequestedNJointControllers() const
1104 {
1105 return ControlThreadDataBufferAttorneyForControlThread::GetRequestedNJointControllers(this);
1106 }
1107
1108 const std::vector<std::size_t>&
1109 ControlThread::rtGetRequestedJointToNJointControllerAssignement() const
1110 {
1111 return ControlThreadDataBufferAttorneyForControlThread::
1112 GetRequestedJointToNJointControllerAssignement(this);
1113 }
1114
1115 void
1116 ControlThread::rtSyncNJointControllerRobot(NJointControllerBase* njctrl)
1117 {
1118 if (njctrl->rtGetRobot())
1119 {
1120 // update joints / nodes
1121 auto& from = rtRobotNodes;
1122 auto& to = njctrl->rtGetRobotNodes();
1123 for (std::size_t i = 0; i < from.size(); ++i)
1124 {
1125 to.at(i)->copyPoseFrom(from.at(i));
1126 }
1127
1128 // update global root pose
1129 njctrl->rtGetRobot()->setGlobalPose(rtRobot->getGlobalPose(), false);
1130 }
1131 }
1132
1133 void
1134 ControlThread::dumpRtControllerSetup(
1135 std::ostream& out,
1136 const std::string& indent,
1137 const std::vector<JointController*>& activeJCtrls,
1138 const std::vector<std::size_t>& assignement,
1139 const std::vector<NJointControllerBase*>& activeNJCtrls) const
1140 {
1141 out << indent << "JointControllers:\n";
1142 {
1143 const auto& cdevs = rtGetControlDevices();
1144 for (std::size_t i = 0; i < cdevs.size(); ++i)
1145 {
1146 const JointController* jctrl = activeJCtrls.at(i);
1147 out << indent << "\t(" << i << ")\t" << cdevs.at(i)->getDeviceName() << ":\n"
1148 << indent << "\t\t Controller: " << jctrl->getControlMode() << " (" << jctrl
1149 << ")\n"
1150 << indent << "\t\t Assigned NJoint: " << assignement.at(i) << "\n";
1151 }
1152 }
1153 out << indent << "NJointControllers:\n";
1154 {
1155 for (std::size_t i = 0; i < activeNJCtrls.size(); ++i)
1156 {
1157 const auto* njctrl = activeNJCtrls.at(i);
1158 out << indent << "\t(" << i << ")\t";
1159 if (njctrl)
1160 {
1161 out << njctrl->rtGetInstanceName() << " (" << njctrl << "):"
1162 << "\t Class: " << njctrl->rtGetClassName() << "\n";
1163 }
1164 else
1165 {
1166 out << " (" << njctrl << ")\n";
1167 }
1168 }
1169 }
1170 }
1171
1172 std::string
1173 ControlThread::dumpRtState() const
1174 {
1175 std::stringstream str;
1176 str << "state requested\n";
1177 dumpRtControllerSetup(str,
1178 "\t",
1179 rtGetRequestedJointControllers(),
1180 rtGetRequestedJointToNJointControllerAssignement(),
1181 rtGetRequestedNJointControllers());
1182
1183 str << "state before rtSwitchControllerSetup() was called\n";
1184 dumpRtControllerSetup(str,
1185 "\t",
1186 preSwitchSetup_ActivatedJointControllers,
1187 preSwitchSetup_ActivatedJointToNJointControllerAssignement,
1188 preSwitchSetup_ActivatedNJointControllers);
1189
1190 str << "state after rtSwitchControllerSetup() was called\n";
1191 dumpRtControllerSetup(str,
1192 "\t",
1193 postSwitchSetup_ActivatedJointControllers,
1194 postSwitchSetup_ActivatedJointToNJointControllerAssignement,
1195 postSwitchSetup_ActivatedNJointControllers);
1196
1197 str << "state now\n";
1198 dumpRtControllerSetup(str,
1199 "\t",
1200 rtGetActivatedJointControllers(),
1201 rtGetActivatedJointToNJointControllerAssignement(),
1202 rtGetActivatedNJointControllers());
1203
1204 str << VAROUT(rtSwitchControllerSetupChangedControllers) << "\n";
1205 str << VAROUT(numberOfInvalidTargetsInThisIteration) << "\n";
1206 return str.str();
1207 }
1208
1209 void
1211 {
1212 const ConstSensorDevicePtr globalPoseSensorDevice =
1214 if (not globalPoseSensorDevice)
1215 {
1216 return;
1217 }
1218
1219 const auto* const sensorValue =
1220 globalPoseSensorDevice->getSensorValue()->asA<SensorValueGlobalRobotPose>();
1221 if (sensorValue == nullptr)
1222 {
1223 return;
1224 }
1225
1226 const auto global_T_robot = sensorValue->global_T_root;
1227 rtSetRobotGlobalPose(global_T_robot, false);
1228 }
1229
1230 void
1231 ControlThread::rtSetRobotGlobalPose(const Eigen::Matrix4f& gp, bool updateRobot)
1232 {
1233 rtRobot->setGlobalPose(gp, updateRobot);
1234 }
1235
1236 void
1238 {
1239 ControlThreadDataBufferAttorneyForControlThread::RTSetJointController(this, c, index);
1240 }
1241} // namespace armarx::RobotUnitModule
#define ARMARX_RT_LOGF_ERROR(...)
#define ARMARX_RT_LOGF_WARNING(...)
uint8_t index
#define VAROUT(x)
constexpr T c
std::string str(const T &t)
Property< PropertyType > getProperty(const std::string &name)
The ControlDevice class represents a logical unit accepting commands via its JointControllers.
JointController * rtGetJointStopMovementController()
virtual void rtSetActiveJointController(JointController *jointCtrl)
Activates the given JointController for this device.
JointController * rtGetJointEmergencyStopController()
JointController * rtGetActiveJointController()
const std::vector< JointController * > & rtGetJointControllers()
void _copyTo(std::unique_ptr< T > &target) const
The JointController class represents one joint in one control mode.
virtual ControlTargetBase * getControlTarget()=0
std::size_t rtGetHardwareControlModeHash() const
virtual void rtMarkRtHandleInvalidTargetsEnd()=0
virtual void rtMarkRtRunJointControllersEnd()=0
virtual void rtMarkRtHandleInvalidTargetsStart()=0
virtual void rtMarkRtUpdateSensorAndControlBufferEnd()=0
virtual void rtMarkRtRunNJointControllersStart()=0
virtual void rtMarkRtReadSensorDeviceValuesEnd()=0
virtual void rtMarkRtResetAllTargetsStart()=0
virtual void rtMarkRtUpdateSensorAndControlBufferStart()=0
virtual void rtMarkRtReadSensorDeviceValuesStart()=0
virtual void rtMarkRtRunNJointControllersEnd()=0
virtual void rtMarkRtRunJointControllersStart()=0
virtual void rtMarkRtSwitchControllerSetupEnd()=0
virtual void rtMarkRtSwitchControllerSetupStart()=0
virtual void rtMarkRtResetAllTargetsEnd()=0
This class allows minimal access to private members of ControlThreadDataBuffer in a sane fashion for ...
This Module manages all communication into and out of the ControlThread.
This Module manages the ControlThread.
EmergencyStopState getEmergencyStopState() const
Returns the ControlThread's target EmergencyStopState.
void rtSetJointController(JointController *c, std::size_t index)
Activate a joint controller from the rt loop (only works in switch mode RTThread)
void setEmergencyStopState(EmergencyStopState state)
Sets the EmergencyStopState.
const std::vector< ControlDevicePtr > & rtGetControlDevices() const
Returns all ControlDevices.
const std::vector< SensorDevicePtr > & rtGetSensorDevices()
Returns all SensorDevices.
void rtResetAllTargets()
Calls rtResetTarget for all active Joint controllers.
void rtUpdateSensorAndControlBuffer(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
Updates the current SensorValues and ControlTargets for code running outside of the ControlThread.
void rtHandleInvalidTargets()
Deactivates all NJointControllers generating invalid targets.
RTThreadTimingsSensorDevice & rtGetThreadTimingsSensorDevice()
Returns the RTThreadTimingsSensorDevice.
virtual void rtDeactivatedNJointControllerBecauseOfError(const NJointControllerBasePtr &)
Hook for deriving classes (called AFTER a NJointControllerBase is deactivated due to an error)
bool rtSwitchControllerSetup(SwitchControllerMode mode=SwitchControllerMode::IceRequests)
Changes the set of active controllers.
void rtDeactivateAssignedNJointControllerBecauseOfError(std::size_t ctrlDevIndex)
Searches for the NJointControllerBase responsible for the given JointController and deactivates it.
const VirtualRobot::RobotPtr & rtGetRobot() const
Returns the simox robot used in the control thread.
void rtSetEmergencyStopState(EmergencyStopState state)
Set an EmergencyStopState request.
void rtDeactivateNJointControllerBecauseOfError(std::size_t nJointCtrlIndex)
Deactivates a NJointControllerBase and sets all used ControlDevices to EmergencyStop.
EmergencyStopState getRtEmergencyStopState() const
Returns the ControlThread's EmergencyStopState.
void rtRunNJointControllers(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
Runs NJoint controllers.
bool rtIsInEmergencyStop() const
Returns whether the rt thread is in emergency stop.
void rtSetRobotGlobalPose(const Eigen::Matrix4f &gp, bool updateRobot=true)
void rtRunJointControllers(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
Runs Joint controllers and writes target values to ControlDevices.
virtual void rtPostReadSensorDeviceValues(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
Execute code after updating the sensor values.
void rtReadSensorDeviceValues(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
Calls rtReadSensorValues for all SensorDevices.
This class allows minimal access to private members of Devices in a sane fashion for ControlThread.
This Module manages sensor and control devices for a RobotUnit and only allows save and sane access.
This class allows minimal access to private members of Devices in a sane fashion for ControlThread.
This Module handles some general management tasks.
T & _module()
Returns this as ref to the given type.
void throwIfInControlThread(const std::string &fnc) const
Throws if the current thread is the ControlThread.
static constexpr std::size_t IndexSentinel()
Returns a sentinel value for an index (std::numeric_limits<std::size_t>::max())
This class allows minimal access to private members of NJointControllerBase in a sane fashion for Con...
The RobotUnit class manages a robot and its controllers.
Definition RobotUnit.h:192
static IceUtil::Time GetTime(TimeMode timeMode=TimeMode::VirtualTime)
Get the current time.
Definition TimeUtil.cpp:42
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
#define ARMARX_CHECK_LESS(lhs, rhs)
This macro evaluates whether lhs is less (<) than rhs and if it turns out to be false it will throw a...
#define ARMARX_CHECK_NOT_NULL(ptr)
This macro evaluates whether ptr is not null and if it turns out to be false it will throw an Express...
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
#define ARMARX_ERROR
The logging level for unexpected behaviour, that must be fixed.
Definition Logging.h:196
#define ARMARX_VERBOSE
The logging level for verbose information.
Definition Logging.h:187
#define ARMARX_ON_SCOPE_EXIT
Executes given code when the enclosing scope is left.
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
std::shared_ptr< RTFilterBase > RTFilterBasePtr
state::Type from(Eigen::Vector3f targetPosition)
std::string GetHandledExceptionString()
std::vector< std::string > Split(const std::string &source, const std::string &splitBy, bool trimElements=false, bool removeEmptyElements=false)
IceUtil::Time rtNow()
Definition RtTiming.h:40
detail::ControlThreadOutputBufferEntry SensorAndControl
std::shared_ptr< const class SensorDevice > ConstSensorDevicePtr
static constexpr std::size_t Sentinel()
std::vector< std::vector< PropagateConst< ControlTargetBase * > > > control
IceUtil::Time writeTimestamp
Timestamp in wall time (never use the virtual time for this)
std::vector< PropagateConst< SensorValueBase * > > sensors