RobotVisualizationController.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 ArmarXGuiPlugins::RobotTrajectoryDesigner::Visualization
17  * @author Timo Birr
18  * @date 2018
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
23 
25 
27 
28 #include "VirtualRobot/XML/RobotIO.h"
29 
30 #include "VirtualRobot/RobotNodeSet.h"
31 
32 #include "../KinematicSolver.h"
33 
34 #include "../Environment.h"
35 
36 #include "../Util/OrientationConversion.h"
37 
38 #include "../Visualization/DesignerTrajectoryPlayer.h"
40 
41 #include <QGridLayout>
42 
43 #define ROBOT_UPDATE_TIMER_MS 33
44 
45 
46 using namespace armarx;
47 using namespace VirtualRobot;
48 
49 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
50 /// INITIALIZATION
51 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
53 {
56 }
57 
59 {
60 
61 }
62 
64 {
65  //initialize Attributes
66  this->cs = IKSolver::CartesianSelection::All;
67  this->selectedWayPoint = 0;
68  this->selectedTransition = -1;
69  this->iKCallback = true;
70  this->playerRunning = false;
71 
72 
73  //Initialize Viewer Widget
74  QWidget* viewerParent = new QWidget();
75  this->viewer = RobotVisualizationPtr(new CoinRobotViewerAdapter(viewerParent));
76  this->viewSplitter = new RobotVisualizationWidget(0, viewerParent, viewer);
77  dynamic_cast<QGridLayout*>(parent->layout())->addWidget(viewSplitter, 0, 0, 1, 3);//this needs to be done in order to let Toolbar and view overlap
78  if (environment != NULL && environment->getRobot())
79  {
80  robotChanged(environment->getRobot());
81  }
82  this->setCamera(0);
83  ARMARX_INFO << "RobotTrajectoryDesigner: RobotVisualizationController on init component";
84 }
85 
87 {
88  ARMARX_INFO << "RobotTrajectoryDesigner: RobotVisualizationController on connect component";
89 }
90 
92 {
93  ARMARX_INFO << "RobotTrajectoryDesigner: RobotVisualizationController on disconnect";
94 }
95 
97 {
98  ARMARX_INFO << "RobotTrajectoryDesigner: RobotVisualizationController on exit components";
99 }
100 
102 {
103  //UPDATE WAYPOINT SELECTION
104  if (selectedWayPoint != this->viewer->getSelectedWaypoint())
105  {
106  selectedWayPoint = this->viewer->getSelectedWaypoint();
107  emit wayPointSelected(selectedWayPoint);
108  if (currentTrajectory && static_cast<unsigned>(viewer->getSelectedWaypoint()) < currentTrajectory->getAllUserWaypoints().size())
109  {
110  std::vector<double> angles = currentTrajectory->getUserWaypoint(viewer->getSelectedWaypoint())->getJointAngles();
111  viewer->setManipulator(currentTrajectory->getRns(), std::vector<float>(angles.begin(), angles.end()));
112  }
113  }
114  //UPDATE MANIPULATOR MOVEMENT
115  if (!selectedKinematicChain)
116  {
117  return;
118  }
119  emit manipulatorChanged(viewer->getManipulatorPose());
121  PoseBasePtr destination = PoseBasePtr(new Pose(viewer->getManipulatorPose()));
122  std::string currentRnsName = selectedKinematicChain->getName();
123  std::vector<float> jointAngles = ks->solveRecursiveIK(this->robot->getRobotNodeSet(currentRnsName), robot->getRobotNodeSet(currentRnsName)->getJointValues(), destination, cs);
124  if (jointAngles.size() != 0 && iKCallback)
125  {
126  robot->getRobotNodeSet(currentRnsName)->setJointValues(jointAngles);
127  emit poseReachable(true);
128  emit tcpPoseChanged(robot->getRobotNodeSet(currentRnsName)->getTCP()->getGlobalPose());
129  }
130  else
131  {
132  emit poseReachable(false);
133  }
134 }
135 
137 {
138  viewer->setObserver(ctr);
139 }
140 
141 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
142 /// PARALLEL VIEWS
143 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
145 {
146  this->viewSplitter->addWidget();
147 }
148 
150 {
151  this->viewSplitter->removeWidget();
152 }
153 
154 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
155 /// UPDATING OF VISUALIZATION
156 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
157 
159 {
160  this->environment = environment;
161  robotChanged(environment->getRobot());
162 }
163 
165 {
166  this->robot = robot;
167  if (viewer)
168  {
169  viewer->addRobotVisualization(this->robot, "");
170  }
171  kinematicChainChanged(NULL);
172  this->currentTrajectory = NULL;
173  this->selectedWayPoint = 0;
174  this->selectedTransition = -1;
175  this->setCamera(0);
176 
177 }
178 
180 {
181  /*for (RobotVisualizationPtr visu : viewers)
182  {
183  visu->clearTrajectory();
184  }*/
185  viewer->clearTrajectory();
186 
187 
188  if (!trajectory)
189  {
190  return;
191  }
192 
193  this->currentTrajectory = trajectory;
194  this->kinematicChainChanged(currentTrajectory->getRns());
195  //clearViewers
196 
197 
198  //Add all UserWayPoints
199  int i = 0;
200  if (currentTrajectory->getAllUserWaypoints().size() == 0)
201  {
202  return;
203  }
204  for (UserWaypointPtr currentPoint : currentTrajectory->getAllUserWaypoints())
205  {
206 
207  VirtualRobot::EndEffectorPtr endEffector = robot->getEndEffector(trajectory->getRns()->getTCP()->getName());
208  if (!endEffector)
209  {
210  std::vector<VirtualRobot::EndEffectorPtr> eefs;
211  robot->getEndEffectors(eefs);
212  for (auto eef : eefs)
213  {
214  if (eef->getTcp() == trajectory->getRns()->getTCP())
215  {
216  endEffector = eef;
217  break;
218  }
219  }
220  }
221  Pose localPose = Pose(currentPoint->getPose()->position, currentPoint->getPose()->orientation);
222  if (endEffector)
223  {
224 
225  viewer->addWaypointVisualization(i, PosePtr(new Pose(trajectory->getRns()->getKinematicRoot()->toGlobalCoordinateSystem(localPose.toEigen()))), endEffector);
226  //visu->addWaypointVisualization(i, currentPoint->getPose(), robot->getEndEffector(robot->getRobotNodeSet(trajectory->getRns()->getName())->getTCP()->getName()));
227  }
228  else
229  {
230  viewer->addWaypointVisualization(i, PosePtr(new Pose(trajectory->getRns()->getKinematicRoot()->toGlobalCoordinateSystem(localPose.toEigen()))), NULL);
231  }
232  i++;
233 
234  }
235 
236 
237  //Add all Transitions
238  if (currentTrajectory->getAllUserWaypoints().size() == 1)
239  {
240  return;
241  }
243  for (unsigned int k = 0; k < currentTrajectory->getNrOfUserWaypoints() - 1; k++)
244  {
245  TrajectoryPtr currentTransition = currentTrajectory->getTransition(k)->getTrajectory();
246  std::vector<PoseBasePtr> curve = std::vector<PoseBasePtr>();
247  for (const Trajectory::TrajData& element : *currentTransition)
248  {
249  std::vector<double> jointValues = element.getPositions();
250  PoseBasePtr pose = ks->doForwardKinematic(currentTrajectory->getRns(), jointValues);
251  curve.push_back(pose);
252  }
253  viewer->addTransitionVisualization(k, curve);
254  if (static_cast<signed>(k) == selectedTransition)
255  {
256  viewer->highlightTransitionVisualization(k, curve);
257  }
258  }
259  //ARMARX_INFO << "DEBUG END";
260 }
261 
262 
263 
264 
265 
267 {
268  //TODO find out sphere size
269 }
270 
272 {
274  TrajectoryPtr selectedTransition = currentTrajectory->getTransition(index)->getTrajectory();
275 
276  std::vector<PoseBasePtr> curve = std::vector<PoseBasePtr>();
277 
278  for (const Trajectory::TrajData& element : *selectedTransition)
279  {
280  std::vector<double> jointValues = element.getPositions();
281  PoseBasePtr pose = ks->doForwardKinematic(currentTrajectory->getRns(), jointValues);
282  curve.push_back(pose);
283  }
284  /*for (RobotVisualizationPtr visu : viewers)*/
285  {
286 
287  if (currentTrajectory->getNrOfUserWaypoints() > static_cast<unsigned>(this->selectedTransition + 1) && this->selectedTransition >= 0)
288  {
289  TrajectoryPtr deselectedTransition = currentTrajectory->getTransition(this->selectedTransition)->getTrajectory();
290  std::vector<PoseBasePtr> oldCurve = std::vector<PoseBasePtr>();
291 
292  for (const Trajectory::TrajData& element : *deselectedTransition)
293  {
294 
295  std::vector<double> jointValues = element.getPositions();
296  PoseBasePtr pose = ks->doForwardKinematic(currentTrajectory->getRns(), jointValues);
297  oldCurve.push_back(pose);
298  }
299  viewer->removeTransitionVisualization(this->selectedTransition);
300  viewer->addTransitionVisualization(this->selectedTransition, oldCurve);
301  }
302  viewer->highlightTransitionVisualization(index, curve);
303  }
304  this->selectedTransition = index;
305 }
306 
308 {
309  viewer->clearTrajectory();
310  this->currentTrajectory = NULL;
311 }
312 
313 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
314 /// IK CALLBACK METHODS
315 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
317 {
318  this->cs = IKSolver::CartesianSelection::All;
319  refresh();
320 }
321 
323 {
324  viewer->removeAllWaypointVisualizations();
325  //IKCallback
326 
327  this->selectedKinematicChain = rns;
328 
329  if (selectedKinematicChain)
330  {
331  std::vector<float> jointAngles;
332  jointAngles = std::vector<float>(robot->getRobotNodeSet(this->selectedKinematicChain->getName())->getJointValues());
333  viewer->setManipulator(this->selectedKinematicChain, jointAngles);
334  }
335  this->updateViews(NULL);
336 }
337 
339 {
340  iKCallback = enabled;
341 }
342 
343 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
344 /// CAMERA UPDATING METHODS
345 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
347 {
348  setCamera(0);
349 }
350 
352 {
353  Eigen::Vector3f position;
354  Eigen::Vector3f pointAtA = Eigen::Vector3f(0, 0, 0);
355  Eigen::Vector3f pointAtB;
356 
357  switch (perspective)
358  {
359  case 0 :
360  //HIGH ANGLE
361  position = Eigen::Vector3f(0, 2, 3.5);
362  pointAtB = Eigen::Vector3f(0, 0, 5);
363  break;
364 
365  case 1 :
366  //TOP
367  position = Eigen::Vector3f(0, 0, 4);
368  pointAtB = Eigen::Vector3f(0, -360, 0);
369  break;
370 
371  case 2 :
372  //FRONT
373  position = Eigen::Vector3f(0, 5, 2);
374  pointAtB = Eigen::Vector3f(0, 0, 2);
375  break;
376  case 3 :
377  //BACK
378  position = Eigen::Vector3f(0, -5, 2);
379  pointAtB = Eigen::Vector3f(0, 0, 2);
380  break;
381 
382  case 4 :
383  //LEFT
384  position = Eigen::Vector3f(5, 0, 2);
385  pointAtB = Eigen::Vector3f(0, 0, 2);
386  break;
387  case 5 :
388  //RIGHT
389  position = Eigen::Vector3f(-5, 0, 2);
390  pointAtB = Eigen::Vector3f(0, 0, 2);
391  break;
392  default:
393  position = Eigen::Vector3f(0, 2, 3.5);
394  pointAtB = Eigen::Vector3f(0, 0, 5);
395  }
396  this->viewSplitter->setCameraOfFocused(position, pointAtA, pointAtB);
397  /*RobotVisualizationPtr expectedViewer = viewers[0];
398  expectedViewer->setCamera(position, pointAtA, pointAtB);
399  expectedViewer->updateRobotVisualization();*/
400 
401 }
402 
404 {
405  viewer->setSelectedWaypoint(index);
406  if (currentTrajectory)
407  {
408  ARMARX_WARNING << "robot visualisation controller trying to update selected waypoint";
409  std::vector<double> jA = currentTrajectory->getUserWaypoint(index)->getJointAngles();
410  std::vector<float> jointAngles = std::vector<float>(jA.begin(), jA.end());
411  viewer->setManipulator(currentTrajectory->getRns(), jointAngles);
412  this->cartesianSelectionChanged(currentTrajectory->getUserWaypoint(index)->getIKSelection());
413  }
414 }
415 
416 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
417 /// PLAY TRAJECTORY
418 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
419 
421 {
422  player = DesignerTrajectoryPlayerPtr(new DesignerTrajectoryPlayer(this->viewer, this->robot));
423  player->addTrajectory(currentTrajectory);
424  this->playerStarter();
425 }
426 
427 void RobotVisualizationController::playTrajectories(std::vector<DesignerTrajectoryPtr> trajectories)
428 {
429  player = DesignerTrajectoryPlayerPtr(new DesignerTrajectoryPlayer(this->viewer, this->robot));
430  for (DesignerTrajectoryPtr current : trajectories)
431  {
432  player->addTrajectory(current);
433  }
434  this->playerStarter();
435 }
436 
438 {
439  player = NULL;
440  KinematicSolver::getInstance(NULL, NULL)->syncRobotPrx();
441  updateViews(currentTrajectory);
442  setIKCallbackEnabled(true);
443  viewer->setManipulator(selectedKinematicChain, robot->getRobotNodeSet(selectedKinematicChain->getName())->getJointValues());
444  playerRunning = false;
445  emit trajectoryPlayerNotPlaying(!playerRunning);
446  emit trajectoryPlayerPlaying(playerRunning);
447 }
448 
449 void RobotVisualizationController::playerStarter()
450 {
451  if (playerRunning || !selectedKinematicChain)
452  {
453  return;
454  }
455  playerRunning = true;
456  emit trajectoryPlayerNotPlaying(!playerRunning);
457  emit trajectoryPlayerPlaying(playerRunning);
458  connect(player.get(), SIGNAL(finishedPlayback()), this, SLOT(trajectoryPlayerStopped()));
459  viewer->clearTrajectory();
460  viewer->setManipulator(NULL, std::vector<float>());
461  setIKCallbackEnabled(false);
462  player->startPlayback();
463 }
armarx::RobotVisualizationController::removeView
void removeView()
removeView removes RobotViewer with index
Definition: RobotVisualizationController.cpp:149
armarx::RobotVisualizationController::onExitComponent
void onExitComponent() override
Called on exit, cleans.
Definition: RobotVisualizationController.cpp:96
armarx::UserWaypointPtr
std::shared_ptr< UserWaypoint > UserWaypointPtr
Definition: UserWaypoint.h:137
armarx::RobotVisualizationController::playTrajectories
void playTrajectories(std::vector< DesignerTrajectoryPtr > trajectories)
playTrajectories plays all trajectories at the same time
Definition: RobotVisualizationController.cpp:427
armarx::CoinRobotViewerAdapter
The CoinRobotViewerAdapter class.
Definition: CoinRobotViewerAdapter.h:41
armarx::RobotVisualizationController::onInitComponent
void onInitComponent() override
Initializes the controller.
Definition: RobotVisualizationController.cpp:63
armarx::RobotVisualizationController::wayPointSelected
void wayPointSelected(int index)
wayPointSelected informs all relevant controllers that the currently selected Waypoit has been change...
armarx::RobotVisualizationWidget
The RobotVisualizationWidget class Holds the original viewer and reproduces it tosupport parallel vie...
Definition: RobotVisualizationWidget.h:40
armarx::RobotVisualizationWidget::removeWidget
void removeWidget()
removeWidget removes a view from this Widget
Definition: RobotVisualizationWidget.cpp:93
armarx::RobotVisualizationController::selectedTransitionChanged
void selectedTransitionChanged(int index)
selectedTransitionChanged highlights the Transition with index
Definition: RobotVisualizationController.cpp:271
armarx::navigation::core::Pose
Eigen::Isometry3f Pose
Definition: basic_types.h:31
RobotVisualizationController.h
index
uint8_t index
Definition: EtherCATFrame.h:59
VirtualRobot
Definition: FramedPose.h:43
armarx::PosePtr
IceInternal::Handle< Pose > PosePtr
Definition: Pose.h:306
armarx::RobotVisualizationController::environmentChanged
void environmentChanged(EnvironmentPtr environment)
environmentChanged updates the environment that is currently visualized
Definition: RobotVisualizationController.cpp:158
armarx::Trajectory::TrajData
Definition: Trajectory.h:85
armarx::RobotVisualizationController::addConnection
void addConnection(std::shared_ptr< RobotVisualizationController > ctr)
Definition: RobotVisualizationController.cpp:136
display
Use of this software is granted under one of the following two to be chosen freely by the user Boost Software License Version Marcin Kalicinski Permission is hereby free of to any person or organization obtaining a copy of the software and accompanying documentation covered by this display
Definition: license.txt:11
armarx::RobotVisualizationController::displayAllWayPoints
void displayAllWayPoints(bool display)
displayAllWayPoints Enables Visualization and threfore selection of all waypoints of the current Traj...
Definition: RobotVisualizationController.cpp:266
armarx::RobotVisualizationController::kinematicChainChanged
void kinematicChainChanged(VirtualRobot::RobotNodeSetPtr rns)
kinematicChainChanged removes all visualization from the previously selected Trajectory and changes t...
Definition: RobotVisualizationController.cpp:322
armarx::RobotVisualizationController::trajectoryPlayerPlaying
void trajectoryPlayerPlaying(bool playing)
armarx::RobotVisualizationController::tcpPoseChanged
void tcpPoseChanged(Eigen::Matrix4f globalPose)
tcpPoseChanged informs all releveant controllers about the new global pose of the manipulator
armarx::RobotVisualizationController::poseReachable
void poseReachable(bool reachable)
poseReachable informs all relevant controllers whether the pose of the manipulator is reachable
armarx::RobotVisualizationController::trajectoryPlayerStopped
void trajectoryPlayerStopped()
trajectoryPlayerStopped restarts the visualization of the whole scene after the debug drawer does not...
Definition: RobotVisualizationController.cpp:437
IceInternal::Handle< Trajectory >
armarx::DesignerTrajectoryPlayerPtr
std::shared_ptr< DesignerTrajectoryPlayer > DesignerTrajectoryPlayerPtr
Definition: DesignerTrajectoryPlayer.h:85
armarx::EnvironmentPtr
std::shared_ptr< Environment > EnvironmentPtr
Definition: Environment.h:29
armarx::RobotVisualizationController::onDisconnectComponent
void onDisconnectComponent() override
Called whenever a component is disconnected.
Definition: RobotVisualizationController.cpp:91
armarx::RobotVisualizationController::RobotVisualizationController
RobotVisualizationController(QWidget *parent)
RobotVisualizationController creates a new RobotVisualizationController.
Definition: RobotVisualizationController.cpp:52
armarx::RobotVisualizationWidget::setCameraOfFocused
void setCameraOfFocused(Eigen::Vector3f position, Eigen::Vector3f pointAtA, Eigen::Vector3f pointAtB)
setCameraOfFocused sets the camera of the viewer that is currently focused (the viewer that was last ...
Definition: RobotVisualizationWidget.cpp:135
armarx::RobotVisualizationController::robotChanged
void robotChanged(VirtualRobot::RobotPtr robot)
robotChanged updates the robot model that is currently visualized Removes the robot that is visualize...
Definition: RobotVisualizationController.cpp:164
armarx::DesignerTrajectoryPlayer
Definition: DesignerTrajectoryPlayer.h:37
armarx::NJointTaskSpaceDMPControllerMode::CartesianSelection
CartesianSelection
Definition: ControllerInterface.ice:34
enabled
std::atomic< bool > * enabled
Definition: RemoteGuiWidgetController.cpp:75
armarx::Pose::toEigen
virtual Eigen::Matrix4f toEigen() const
Definition: Pose.cpp:334
armarx::RobotVisualizationController::onConnectComponent
void onConnectComponent() override
Connects all signals and slots of the controller.
Definition: RobotVisualizationController.cpp:86
armarx::RobotVisualizationController::setIKCallbackEnabled
void setIKCallbackEnabled(bool enabled)
setIKCallbackEnabled sets whther the robot Model tries to reach the Pose determined by the Manipulato...
Definition: RobotVisualizationController.cpp:338
armarx::RobotVisualizationController::setCamera
void setCamera()
CAMERA UPDATING METHODS.
Definition: RobotVisualizationController.cpp:346
armarx::RobotVisualizationController::selectedWayPointChanged
void selectedWayPointChanged(int index)
selectedWayPointChanged highlights the waypoint with index and moves the manipulator to its Pose
Definition: RobotVisualizationController.cpp:403
armarx::RobotVisualizationController::trajectoryPlayerNotPlaying
void trajectoryPlayerNotPlaying(bool playing)
trajectoryPlayerNotPlaying
armarx::RobotVisualizationController::clearView
void clearView()
Definition: RobotVisualizationController.cpp:307
armarx::RobotVisualizationController::refresh
void refresh() override
refresh gets all relevant data from subject an updates itself accoringly should be called by subject ...
Definition: RobotVisualizationController.cpp:101
armarx::channels::KinematicUnitObserver::jointAngles
const KinematicUnitDatafieldCreator jointAngles("jointAngles")
armarx::RobotVisualizationPtr
std::shared_ptr< RobotVisualization > RobotVisualizationPtr
Definition: RobotVisualization.h:161
armarx::KinematicSolver::getInstance
static std::shared_ptr< KinematicSolver > getInstance(VirtualRobot::ScenePtr scenario, VirtualRobot::RobotPtr robot)
SINGLETON-FEATURES///////////////////////////////////////////////////////////////////////////////////...
Definition: KinematicSolver.cpp:92
Trajectory.h
armarx::Pose
The Pose class.
Definition: Pose.h:242
armarx::RobotVisualizationController::~RobotVisualizationController
~RobotVisualizationController()
Definition: RobotVisualizationController.cpp:58
armarx::RobotVisualizationController::playTrajectory
void playTrajectory()
PLAY TRAJECTORY.
Definition: RobotVisualizationController.cpp:420
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
armarx::DesignerTrajectoryPtr
std::shared_ptr< DesignerTrajectory > DesignerTrajectoryPtr
Definition: DesignerTrajectory.h:165
armarx::RobotVisualizationControllerPtr
std::shared_ptr< RobotVisualizationController > RobotVisualizationControllerPtr
Definition: RobotVisualizationController.h:241
armarx::RobotVisualizationController::manipulatorChanged
void manipulatorChanged(Eigen::Matrix4f globalPose)
manipulatorChanged informs all relevant controllers that the pose of the manipulator has changed and ...
armarx::KinematicSolverPtr
std::shared_ptr< KinematicSolver > KinematicSolverPtr
Definition: KinematicSolver.h:235
Logging.h
armarx::RobotVisualizationController::addView
void addView()
PARALLEL VIEWS.
Definition: RobotVisualizationController.cpp:144
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
TrajectoryController.h
armarx::RobotVisualizationWidget::addWidget
void addWidget()
addWidget adds a new View by reproducing the original viewer
Definition: RobotVisualizationWidget.cpp:59
armarx::RobotVisualizationController::cartesianSelectionChanged
void cartesianSelectionChanged(VirtualRobot::IKSolver::CartesianSelection cs)
IK CALLBACK METHODS.
Definition: RobotVisualizationController.cpp:316
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
armarx::RobotVisualizationController::updateViews
void updateViews(DesignerTrajectoryPtr trajectory)
UPDATING OF VISUALIZATION.
Definition: RobotVisualizationController.cpp:179
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18