TAMSVIZ
Visualization and annotation tool for ROS
robot.cpp
1 // TAMSVIZ
2 // (c) 2020 Philipp Ruppel
3 
4 #include "robot.h"
5 
6 #include "../core/log.h"
7 #include "../core/transformer.h"
8 #include "../core/workspace.h"
9 #include "../render/mesh.h"
10 #include "shapes.h"
11 
12 #include <moveit/robot_model/robot_model.h>
13 #include <moveit/robot_model_loader/robot_model_loader.h>
14 #include <moveit/robot_state/conversions.h>
15 #include <moveit/robot_state/robot_state.h>
16 
17 #include <geometric_shapes/shape_operations.h>
18 
19 #include <assimp/Importer.hpp>
20 #include <assimp/config.h>
21 #include <assimp/postprocess.h>
22 #include <assimp/scene.h>
23 
24 #include <eigen_conversions/eigen_msg.h>
25 
26 static std::shared_ptr<Mesh>
27 createShapeMesh(const urdf::VisualSharedPtr &visual) {
28  auto geometry = visual->geometry;
29  switch (geometry->type) {
30  case urdf::Geometry::SPHERE: {
31  auto *sphere = (const urdf::Sphere *)geometry.get();
32  return std::make_shared<Mesh>(Eigen::Scaling(float(sphere->radius)) *
33  makeSphere(32, 16));
34  }
35  case urdf::Geometry::BOX: {
36  auto *box = (const urdf::Box *)geometry.get();
37  return std::make_shared<Mesh>(
38  Eigen::Scaling(Eigen::Vector3f(box->dim.x * 0.5, box->dim.y * 0.5,
39  box->dim.z * 0.5)) *
40  makeBox());
41  }
42  case urdf::Geometry::CYLINDER: {
43  auto *cylinder = (const urdf::Cylinder *)geometry.get();
44  return std::make_shared<Mesh>(
45  Eigen::Scaling(Eigen::Vector3f(cylinder->radius, cylinder->radius,
46  cylinder->length * 0.5)) *
47  makeCylinder(32));
48  }
49  }
50  return nullptr;
51 }
52 
53 struct RobotLink {
54  std::shared_ptr<Material> material = []() {
55  ObjectScope ws;
56  return std::make_shared<Material>();
57  }();
58  Eigen::Isometry3d pose = Eigen::Isometry3d::Identity();
59  const moveit::core::LinkModel *moveit_link = nullptr;
60  size_t link_index = 0;
61  size_t part_index = 0;
62  Frame frame;
63  std::shared_ptr<Mesh> mesh;
64  RobotLink(const moveit::core::LinkModel *moveit_link,
65  const Eigen::Isometry3d &pose, const std::shared_ptr<Mesh> &mesh)
66  : moveit_link(moveit_link), link_index(moveit_link->getLinkIndex()),
67  pose(pose), mesh(mesh), frame(moveit_link->getName()) {}
68 };
69 
70 struct RobotModel {
71  moveit::core::RobotModelConstPtr moveit_robot;
72  std::vector<std::shared_ptr<RobotLink>> links;
73  RobotModel(const std::string &name, RobotModelImportOptions import_options) {
74  {
75  robot_model_loader::RobotModelLoader moveit_loader(name, false);
76  moveit_robot = moveit_loader.getModel();
77  if (!moveit_robot) {
78  LOG_ERROR("failed to load robot model " << name);
79  return;
80  }
81  }
82  auto urdf_model = moveit_robot->getURDF();
83  for (auto &urdf_link_pair : urdf_model->links_) {
84  auto urdf_link = urdf_link_pair.second;
85  if (const moveit::core::LinkModel *moveit_link =
86  moveit_robot->getLinkModel(urdf_link->name)) {
87  for (auto &urdf_visual : urdf_link->visual_array) {
88  if (urdf_visual->geometry) {
89  size_t part_index = 0;
90  auto rot = urdf_visual->origin.rotation;
91  auto pos = urdf_visual->origin.position;
92  Eigen::Isometry3d visual_pose =
93  Eigen::Isometry3d(Eigen::Translation3d(pos.x, pos.y, pos.z)) *
94  Eigen::Isometry3d(
95  Eigen::Quaterniond(rot.w, rot.x, rot.y, rot.z));
96  if (auto mesh = createShapeMesh(urdf_visual)) {
97  auto link = new RobotLink(moveit_link, visual_pose, mesh);
98  if (auto mat = urdf_visual->material) {
99  LockScope ws;
100  LOG_DEBUG("urdf material color "
101  << urdf_link->name << " " << mat->color.r << " "
102  << mat->color.g << " " << mat->color.b << " "
103  << mat->color.a);
104  link->material->color().r() = mat->color.r;
105  link->material->color().g() = mat->color.g;
106  link->material->color().b() = mat->color.b;
107  link->material->color().a() = mat->color.a;
108  link->material->texture() = mat->texture_filename;
109  } else {
110  LOG_DEBUG("no material for " << urdf_link->name);
111  }
112  links.emplace_back(link);
113  } else if (urdf_visual->geometry->type == urdf::Geometry::MESH) {
114  auto *urdf_mesh = (const urdf::Mesh *)urdf_visual->geometry.get();
115  if (urdf_mesh->filename.empty()) {
116  LOG_ERROR("empty mesh file name")
117  } else {
118  // LOG_INFO("loading mesh " << urdf_mesh->filename);
119  std::string data;
120  try {
121  loadResource(urdf_mesh->filename, data);
122  } catch (std::exception &ex) {
123  LOG_ERROR("failed to read mesh file " << urdf_mesh->filename);
124  }
125  if (data.empty()) {
126  LOG_ERROR("failed to read mesh file " << urdf_mesh->filename);
127  } else {
128  std::string assimp_hint;
129  if (auto *h =
130  std::strrchr(urdf_mesh->filename.c_str(), '.')) {
131  assimp_hint = h + 1;
132  for (auto &c : assimp_hint) {
133  c = std::tolower(c);
134  }
135  if (std::strstr(assimp_hint.c_str(), "stl")) {
136  assimp_hint = "stl";
137  }
138  }
139  // LOG_DEBUG("import hint " << assimp_hint);
140  auto import_flags =
141  aiProcessPreset_TargetRealtime_MaxQuality |
142  aiProcess_Triangulate;
143  Assimp::Importer ai_importer;
144  ai_importer.SetPropertyFloat(
145  AI_CONFIG_PP_GSN_MAX_SMOOTHING_ANGLE, 60.0);
146  if (import_options.recomputeNormals()) {
147  ai_importer.SetPropertyInteger(
148  AI_CONFIG_PP_RVC_FLAGS,
149  aiComponent_NORMALS |
150  aiComponent_TANGENTS_AND_BITANGENTS);
151  import_flags |= aiProcess_RemoveComponent;
152  }
153  // ai_importer.SetPropertyFloat(
154  // AI_CONFIG_PP_GSN_MAX_SMOOTHING_ANGLE, 60.0);
155  // ai_importer.SetPropertyBool(AI_CONFIG_FAVOUR_SPEED,
156  // true);
157  /*ai_importer.SetPropertyInteger(
158  AI_CONFIG_PP_RVC_FLAGS,
159  aiComponent_NORMALS |
160  aiComponent_TANGENTS_AND_BITANGENTS);*/
161  auto *ai_scene = ai_importer.ReadFileFromMemory(
162  data.data(), data.size(), import_flags,
163  assimp_hint.c_str());
164  if (ai_scene) {
165  if (!import_options.recomputeNormals() &&
166  import_options.smoothNormals()) {
167  bool has_normapmaps = false;
168  for (size_t i = 0; i < ai_scene->mNumMaterials; i++) {
169  if (ai_scene->mMaterials[i]->GetTextureCount(
170  aiTextureType_NORMALS) > 0) {
171  has_normapmaps = true;
172  }
173  }
174  if (!has_normapmaps) {
175  ai_importer.FreeScene();
176  ai_importer.SetPropertyInteger(
177  AI_CONFIG_PP_RVC_FLAGS,
178  aiComponent_NORMALS |
179  aiComponent_TANGENTS_AND_BITANGENTS);
180  /*ai_scene = ai_importer.ApplyPostProcessing(
181  aiProcessPreset_TargetRealtime_MaxQuality |
182  aiProcess_Triangulate |
183  aiProcess_RemoveComponent);*/
184  import_flags |= aiProcess_RemoveComponent;
185  ai_scene = ai_importer.ReadFileFromMemory(
186  data.data(), data.size(), import_flags,
187  assimp_hint.c_str());
188  }
189  }
190  std::function<void(const Eigen::Isometry3d &,
191  const aiNode *)>
192  load;
193  load = [&](const Eigen::Isometry3d &parent_pose,
194  const aiNode *node) {
195  // LOG_DEBUG("mesh node " << urdf_mesh->filename << " "
196  // << node->mName.C_Str());
197  Eigen::Matrix4d pose_matrix = Eigen::Matrix4d::Identity();
198  for (size_t row = 0; row < 4; row++) {
199  for (size_t col = 0; col < 4; col++) {
200  pose_matrix(row, col) =
201  node->mTransformation[row][col];
202  }
203  }
204  // LOG_INFO(pose_matrix);
205  // LOG_INFO(Eigen::Isometry3d(pose_matrix).matrix());
206  Eigen::Isometry3d pose =
207  parent_pose * Eigen::Isometry3d(pose_matrix);
208  for (size_t node_mesh_index = 0;
209  node_mesh_index < node->mNumMeshes;
210  node_mesh_index++) {
211  auto *ai_mesh =
212  ai_scene->mMeshes[node->mMeshes[node_mesh_index]];
213  MeshData mesh_data;
214  for (size_t i = 0; i < ai_mesh->mNumVertices; i++) {
215  mesh_data.positions.push_back(Eigen::Vector3f(
216  ai_mesh->mVertices[i].x, ai_mesh->mVertices[i].y,
217  ai_mesh->mVertices[i].z));
218  if (ai_mesh->mNormals) {
219  mesh_data.normals.push_back(Eigen::Vector3f(
220  ai_mesh->mNormals[i].x, ai_mesh->mNormals[i].y,
221  ai_mesh->mNormals[i].z));
222  }
223  if (ai_mesh->mTextureCoords[0]) {
224  mesh_data.texcoords.push_back(Eigen::Vector2f(
225  ai_mesh->mTextureCoords[0][i].x,
226  ai_mesh->mTextureCoords[0][i].y));
227  }
228  if (ai_mesh->mTangents) {
229  mesh_data.tangents.push_back(
230  Eigen::Vector3f(ai_mesh->mTangents[i].x,
231  ai_mesh->mTangents[i].y,
232  ai_mesh->mTangents[i].z));
233  }
234  if (ai_mesh->mBitangents) {
235  mesh_data.bitangents.push_back(
236  Eigen::Vector3f(ai_mesh->mBitangents[i].x,
237  ai_mesh->mBitangents[i].y,
238  ai_mesh->mBitangents[i].z));
239  }
240  }
241  for (size_t i = 0; i < ai_mesh->mNumFaces; i++) {
242  if (ai_mesh->mFaces[i].mNumIndices == 3) {
243  for (size_t j = 0; j < 3; j++) {
244  mesh_data.indices.push_back(
245  ai_mesh->mFaces[i].mIndices[j]);
246  }
247  } else if (ai_mesh->mFaces[i].mNumIndices > 3) {
248  LOG_ERROR("invalid triangle "
249  << ai_mesh->mFaces[i].mNumIndices);
250  }
251  }
252  // mesh_data.computeNormals();
253  if (mesh_data.indices.empty() ||
254  mesh_data.positions.empty()) {
255  LOG_WARN("empty mesh " << urdf_mesh->filename << " "
256  << node->mName.C_Str());
257  } else {
258  // auto link = std::make_shared<RobotLink>(
259  // moveit_link, pose, mesh_data);
260  auto link = std::shared_ptr<RobotLink>(
261  new RobotLink(moveit_link, pose,
262  std::make_shared<Mesh>(mesh_data)));
263  ObjectScope ws;
264  auto *ai_material =
265  ai_scene->mMaterials[ai_mesh->mMaterialIndex];
266  {
267  aiColor4D color;
268  if (aiGetMaterialColor(ai_material,
269  AI_MATKEY_COLOR_DIFFUSE,
270  &color) == AI_SUCCESS) {
271  link->material->color().r() = color.r;
272  link->material->color().g() = color.g;
273  link->material->color().b() = color.b;
274  }
275  }
276  auto tex = [&](std::string &url, aiTextureType type) {
277  if (ai_material->GetTextureCount(type) > 0) {
278  aiString str;
279  ai_material->GetTexture(type, 0, &str);
280  // TODO: ???
281  if (const char *new_end = std::strrchr(
282  urdf_mesh->filename.c_str(), '/')) {
283  url =
284  std::string(
285  urdf_mesh->filename.c_str(),
286  new_end - urdf_mesh->filename.c_str()) +
287  "/" + str.C_Str();
288  } else {
289  url = str.C_Str();
290  }
291  }
292  };
293  tex(link->material->texture(), aiTextureType_DIFFUSE);
294  tex(link->material->normals(), aiTextureType_NORMALS);
295  link->part_index = ++part_index;
296  links.push_back(link);
297  }
298  }
299  for (size_t i = 0; i < node->mNumChildren; i++) {
300  load(pose, node->mChildren[i]);
301  }
302  };
303  ai_scene->mRootNode->mTransformation = aiMatrix4x4();
304  load(visual_pose *
305  Eigen::Isometry3d(Eigen::Scaling(Eigen::Vector3d(
306  urdf_mesh->scale.x, urdf_mesh->scale.y,
307  urdf_mesh->scale.z))),
308  ai_scene->mRootNode);
309  // LOG_INFO("mesh successfully loaded "
310  // << urdf_mesh->filename);
311  } else {
312  LOG_ERROR("failed to decode mesh " << urdf_mesh->filename);
313  }
314  }
315  }
316  } else {
317  LOG_ERROR(" failed to create geometry for link "
318  << urdf_link->name);
319  }
320  }
321  }
322  } else {
323  LOG_ERROR("link not found " << urdf_link->name);
324  }
325  }
326  LOG_SUCCESS("robot model loaded");
327  }
328 };
329 
331  std::unordered_set<std::string> variable_names;
332  std::vector<std::shared_ptr<MeshRenderer>> mesh_renderers;
333  std::shared_ptr<RobotModel> robot_model;
334  moveit::core::RobotState moveit_state;
335  RobotState(const std::shared_ptr<RobotModel> &robot_model,
336  std::shared_ptr<MaterialOverride> material_override)
337  : robot_model(robot_model), moveit_state(robot_model->moveit_robot) {
338  moveit_state.setToDefaultValues();
339  {
340  ObjectScope ws;
341  for (size_t i = 0; i < robot_model->links.size(); i++) {
342  mesh_renderers.push_back(create<MeshRenderer>(
343  robot_model->links.at(i)->mesh, robot_model->links.at(i)->material,
344  material_override));
345  }
346  }
347  for (auto &n : moveit_state.getVariableNames()) {
348  variable_names.insert(n);
349  }
350  }
351 };
352 
353 void RobotDisplayBase::renderSync(const RenderSyncContext &context) {
354  MeshDisplayBase::renderSync(context);
355  bool invalidated = _invalidated.poll();
356  if (invalidated || _watcher.changed(description(), importOptions()) ||
357  !_robot_model_loader) {
358  static auto manager =
359  std::make_shared<ResourceManager<Loader<RobotModel>, std::string,
361  _robot_model_loader = manager->load(description(), importOptions());
362  if (invalidated) {
363  _robot_model_loader->clear();
364  }
365  _robot_state = nullptr;
366  GlobalEvents::instance()->redraw();
367  }
368  if (_robot_state) {
369  bool double_sided = doubleSided();
370  for (auto &r : _robot_state->mesh_renderers) {
371  r->options().double_sided = double_sided;
372  }
373  }
374 }
375 
376 void RobotDisplayBase::renderAsync(const RenderAsyncContext &context) {
377  MeshDisplayBase::renderAsync(context);
378  if (!_robot_state && _robot_model_loader) {
379  if (auto robot_model = _robot_model_loader->load()) {
380  if (robot_model->moveit_robot) {
381  _robot_state =
382  node()->create<RobotState>(robot_model, _material_override);
383  GlobalEvents::instance()->redraw();
384  }
385  }
386  }
387 }
388 
390  std::mutex _mutex;
391  std::unordered_map<std::string, double> _positions, _temp;
392  void push(const sensor_msgs::JointState &message) {
393  for (size_t i = 0; i < message.name.size() && i < message.position.size();
394  i++) {
395  _temp[message.name.at(i)] = message.position.at(i);
396  }
397  }
398 
399 public:
400  virtual void push(const std::shared_ptr<const Message> &msg, int64_t start,
401  int64_t end) override {
402  if (auto message = msg->instantiate<sensor_msgs::JointState>()) {
403  push(*message);
404  }
405  if (auto message = msg->instantiate<moveit_msgs::DisplayRobotState>()) {
406  push(message->state.joint_state);
407  }
408  }
409  virtual void commit() override {
410  std::lock_guard<std::mutex> lock(_mutex);
411  _positions = _temp;
412  }
413  void apply(RobotState &robot_state) {
414  std::lock_guard<std::mutex> lock(_mutex);
415  for (auto &pair : _positions) {
416  if (robot_state.variable_names.find(pair.first) !=
417  robot_state.variable_names.end()) {
418  robot_state.moveit_state.setVariablePosition(pair.first, pair.second);
419  }
420  }
421  }
422 };
423 
424 void RobotStateDisplayBase::refreshTopic(const std::string &topic) {
425  if (!_subscriber || topic != _subscriber->topic()) {
426  _subscriber = std::make_shared<TimeSeriesSubscriber>(topic);
427  _subscriber->duration(0.5);
428  _listener = std::make_shared<RobotStateTimeSeriesListener>();
429  _subscriber->addListener(_listener);
430  }
431 }
432 
433 void RobotStateDisplayBase::renderSync(const RenderSyncContext &context) {
434  if (_robot_state && _listener) {
435  _listener->apply(*_robot_state);
436  for (size_t i = 0; i < _robot_state->robot_model->links.size(); i++) {
437  auto &link = _robot_state->robot_model->links[i];
438  _robot_state->mesh_renderers.at(i)->pose(
439  pose_temp *
440  Eigen::Isometry3d(
441  _robot_state->moveit_state
442  .getGlobalLinkTransform(
443  _robot_state->robot_model->moveit_robot->getLinkModel(
444  link->link_index))
445  .matrix()) *
446  link->pose);
447  _robot_state->mesh_renderers.at(i)->show();
448  }
449  }
450  RobotDisplayBase::renderSync(context);
451 }
452 
453 void DisplayRobotStateDisplay::renderSync(const RenderSyncContext &context) {
454  // _display_robot_state_message = topic().message();
455  auto message = topic().message();
456  if (_robot_state && message) {
457  try {
458  moveit::core::robotStateMsgToRobotState(message->state,
459  _robot_state->moveit_state);
460  } catch (const std::exception &ex) {
461  LOG_ERROR(ex.what());
462  }
463  for (size_t i = 0; i < _robot_state->robot_model->links.size(); i++) {
464  auto &link = _robot_state->robot_model->links[i];
465  _robot_state->mesh_renderers.at(i)->pose(
466  pose_temp *
467  Eigen::Isometry3d(
468  _robot_state->moveit_state
469  .getGlobalLinkTransform(
470  _robot_state->robot_model->moveit_robot->getLinkModel(
471  link->link_index))
472  .matrix()) *
473  link->pose);
474  _robot_state->mesh_renderers.at(i)->show();
475  }
476  }
477  RobotDisplayBase::renderSync(context);
478 }
479 
480 void DisplayRobotStateDisplay::renderAsync(const RenderAsyncContext &context) {
481  RobotDisplayBase::renderAsync(context);
482 }
483 
484 /*
485 void RobotTrajectoryDisplay::renderSync(const RenderSyncContext &context) {
486 
487  auto display_trajectory_message = topic().message();
488  if (_trajectory_watcher.changed(display_trajectory_message)) {
489  _frame_index = 0;
490  }
491 
492  size_t frame_index = 0;
493  if (_robot_state && display_trajectory_message) {
494  for (auto &robot_trajectory : display_trajectory_message->trajectory) {
495  auto &joint_trajectory = robot_trajectory.joint_trajectory;
496  for (auto &point : joint_trajectory.points) {
497  if (_frame_index == frame_index) {
498  for (size_t ijoint = 0; ijoint < joint_trajectory.joint_names.size();
499  ijoint++) {
500  if (ijoint < point.positions.size()) {
501  _robot_state->moveit_state.setVariablePosition(
502  joint_trajectory.joint_names[ijoint],
503  point.positions[ijoint]);
504  }
505  }
506  }
507  frame_index++;
508  }
509  }
510  }
511  _frame_index++;
512  if (_frame_index >= frame_index) {
513  _frame_index = 0;
514  }
515 
516  if (_robot_state) {
517  for (size_t i = 0; i < _robot_state->robot_model->links.size(); i++) {
518  auto &link = _robot_state->robot_model->links[i];
519  _robot_state->mesh_renderers.at(i)->pose(
520  pose_temp *
521  Eigen::Isometry3d(
522  _robot_state->moveit_state
523  .getGlobalLinkTransform(
524  _robot_state->robot_model->moveit_robot->getLinkModel(
525  link->link_index))
526  .matrix()) *
527  link->pose);
528  _robot_state->mesh_renderers.at(i)->show();
529  }
530  }
531 
532  RobotDisplayBase::renderSync(context);
533 }
534 */
535 
536 void RobotTrajectoryDisplay::renderSync(const RenderSyncContext &context) {
537  _display_trajectory_message = topic().message();
538  _max_steps = maxSteps();
539  _show_all = showAllStates();
540  if (_update_parameter_watcher.changed(showAllStates(), speed())) {
541  std::unique_lock<std::mutex> lock(_update_mutex);
542  _update_show_all = showAllStates();
543  _update_speed = speed();
544  _update_condition.notify_all();
545  }
546  RobotDisplayBase::renderSync(context);
547 }
548 
549 void RobotTrajectoryDisplay::renderAsync(const RenderAsyncContext &context) {
550  std::shared_ptr<RobotModel> robot_model;
551  if (_robot_model_loader) {
552  robot_model = _robot_model_loader->load();
553  }
554  /*
555  size_t current_frame = 0;
556  if (!_show_all) {
557  current_frame =
558  (size_t)std::fmod(ros::WallTime::now().toSec(), _frame_time);
559  }
560  */
561  if (_trajectory_watcher.changed(_display_trajectory_message, _max_steps,
562  robot_model)) {
563  _trajectory.clear();
564  if (robot_model && _display_trajectory_message) {
565  // LOG_DEBUG("new trajectory");
566  if (robot_model->moveit_robot) {
567 
568  /*
569  ros::Time current_frame_time;
570  {
571  {
572  size_t joint_frame_count = 0;
573  size_t md_frame_count = 0;
574  for (auto &robot_trajectory :
575  _display_trajectory_message->trajectory) {
576  joint_frame_count +=
577  robot_trajectory.joint_trajectory.points.size();
578  md_frame_count +=
579  robot_trajectory.multi_dof_joint_trajectory.points.size();
580  }
581  size_t frame_count = std::max(
582  size_t(1), std::max(md_frame_count, joint_frame_count));
583  current_frame = current_frame % frame_count;
584  }
585  }
586  */
587 
588  /*
589  ros::Duration display_time = ros::Duration(0);
590  if (!_show_all) {
591  ros::Duration trajectory_duration = ros::Duration(0.0);
592  {
593  for (auto &robot_trajectory :
594  _display_trajectory_message->trajectory) {
595  ros::Duration duration = ros::Duration(0.0);
596  if (!robot_trajectory.joint_trajectory.points.empty()) {
597  duration = std::max(
598  duration, robot_trajectory.joint_trajectory.points.back()
599  .time_from_start);
600  }
601  if (!robot_trajectory.multi_dof_joint_trajectory.points.empty()) {
602  duration = std::max(
603  duration,
604  robot_trajectory.multi_dof_joint_trajectory.points.back()
605  .time_from_start);
606  }
607  trajectory_duration += duration;
608  }
609  }
610  display_time = ros::Duration(
611  std::fmod(ros::Time::now().toSec(),
612  std::max(0.001, trajectory_duration.toSec())));
613  }
614  */
615 
616  std::map<ros::Duration, std::shared_ptr<RobotState>> states;
617  {
618  ros::Duration start_time = ros::Duration(0.0);
619 
620  for (auto &robot_trajectory :
621  _display_trajectory_message->trajectory) {
622 
623  {
624  auto &joint_trajectory = robot_trajectory.joint_trajectory;
625  for (size_t iframe = 0; iframe < joint_trajectory.points.size();
626  iframe++) {
627  auto &point = joint_trajectory.points[iframe];
628  auto &robot_state = states[start_time + point.time_from_start];
629  if (!robot_state) {
630  robot_state = node()->create<RobotState>(robot_model,
631  _material_override);
632  robot_state->moveit_state.setToDefaultValues();
633  try {
634  moveit::core::robotStateMsgToRobotState(
635  _display_trajectory_message->trajectory_start,
636  robot_state->moveit_state);
637  } catch (const std::exception &ex) {
638  LOG_ERROR(ex.what());
639  }
640  }
641  for (size_t ijoint = 0;
642  ijoint <
643  robot_trajectory.joint_trajectory.joint_names.size();
644  ijoint++) {
645  if (ijoint < point.positions.size()) {
646  if (robot_state->variable_names.find(
647  robot_trajectory.joint_trajectory
648  .joint_names[ijoint]) !=
649  robot_state->variable_names.end()) {
650  robot_state->moveit_state.setVariablePosition(
651  robot_trajectory.joint_trajectory.joint_names[ijoint],
652  point.positions[ijoint]);
653  }
654  }
655  }
656  }
657  }
658 
659  {
660  auto &md_trajectory = robot_trajectory.multi_dof_joint_trajectory;
661  for (size_t iframe = 0; iframe < md_trajectory.points.size();
662  iframe++) {
663  for (size_t ijoint = 0;
664  ijoint < md_trajectory.joint_names.size(); ijoint++) {
665  auto &joint_name = md_trajectory.joint_names[ijoint];
666  auto &transform =
667  md_trajectory.points[iframe].transforms[ijoint];
668  auto &robot_state =
669  states[start_time +
670  md_trajectory.points[iframe].time_from_start];
671  if (!robot_state) {
672  robot_state = node()->create<RobotState>(
673  robot_model, _material_override);
674  robot_state->moveit_state.setToDefaultValues();
675  try {
676  moveit::core::robotStateMsgToRobotState(
677  _display_trajectory_message->trajectory_start,
678  robot_state->moveit_state);
679  } catch (const std::exception &ex) {
680  LOG_ERROR(ex.what());
681  }
682  }
683  if (auto *joint_model =
684  robot_state->moveit_state.getJointModel(joint_name)) {
685  Eigen::Affine3d pose = Eigen::Affine3d::Identity();
686  tf::transformMsgToEigen(transform, pose);
687  robot_state->moveit_state.setJointPositions(joint_model,
688  pose);
689  }
690  }
691  }
692  }
693 
694  {
695  ros::Duration duration = ros::Duration(0.0);
696  if (!robot_trajectory.joint_trajectory.points.empty()) {
697  duration = std::max(
698  duration, robot_trajectory.joint_trajectory.points.back()
699  .time_from_start);
700  }
701  if (!robot_trajectory.multi_dof_joint_trajectory.points.empty()) {
702  duration = std::max(
703  duration,
704  robot_trajectory.multi_dof_joint_trajectory.points.back()
705  .time_from_start);
706  }
707  start_time += duration;
708  }
709  }
710  }
711 
712  _trajectory.clear();
713  for (auto &pair : states) {
714  auto &robot_state = pair.second;
715  robot_state->moveit_state.update();
716  for (size_t i = 0; i < robot_state->robot_model->links.size(); i++) {
717  auto &link = robot_state->robot_model->links[i];
718  robot_state->mesh_renderers.at(i)->pose(
719  pose_temp *
720  Eigen::Isometry3d(robot_state->moveit_state
721  .getGlobalLinkTransform(
722  robot_state->robot_model->moveit_robot
723  ->getLinkModel(link->link_index))
724  .matrix()) *
725  link->pose);
726  // robot_state->mesh_renderers.at(i)->show();
727  }
728  _trajectory.emplace_back((pair.first - states.begin()->first).toSec(),
729  robot_state);
730  }
731  } else {
732  LOG_WARN("no robot model");
733  }
734  }
735  GlobalEvents::instance()->redraw();
736  {
737  std::unique_lock<std::mutex> lock(_update_mutex);
738  _update_times.clear();
739  for (ssize_t i = 0; i < _trajectory.size(); i++) {
740  _update_times.push_back(_trajectory[i].first -
741  _trajectory[std::max(ssize_t(0), i - 1)].first);
742  }
743  _update_condition.notify_all();
744  }
745  }
746 
747  MeshDisplayBase::renderAsync(context);
748 
749  if (!_trajectory.empty()) {
750  size_t j = 0;
751  {
752  std::unique_lock<std::mutex> lock(_update_mutex);
753  j = _frame_update;
754  }
755  j = (j % _trajectory.size());
756  for (size_t i = 0; i < _trajectory.size(); i++) {
757  auto &pair = _trajectory[i];
758  bool vis = (_show_all || i == j);
759  for (auto &renderer : pair.second->mesh_renderers) {
760  renderer->visible(vis);
761  }
762  }
763  }
764 }
765 
766 RobotTrajectoryDisplay::RobotTrajectoryDisplay() {
767  _update_thread = std::thread([this]() {
768  LOG_DEBUG("start robot trajectory update thread");
769  size_t current_frame_index = 0;
770  std::chrono::steady_clock::time_point last_tick =
771  std::chrono::steady_clock::now();
772  std::unique_lock<std::mutex> lock(_update_mutex);
773  while (true) {
774  if (_update_exit) {
775  break;
776  }
777  if (_update_times.size() < 2 || _update_show_all || _update_speed == 0) {
778  _update_condition.wait(lock);
779  } else {
780  current_frame_index = (current_frame_index % _update_times.size());
781  double update_time = _update_times[current_frame_index];
782  auto timeout =
783  (last_tick + std::chrono::duration<double>(
784  update_time / std::max(1e-12, _update_speed)));
785  if (std::chrono::steady_clock::now() >= timeout) {
786  current_frame_index++;
787  current_frame_index = (current_frame_index % _update_times.size());
788  _frame_update = current_frame_index;
789  last_tick = std::chrono::steady_clock::now();
790  GlobalEvents::instance()->redraw();
791  // LOG_DEBUG("redraw robot trajectory display");
792  } else {
793  _update_condition.wait_until(lock, timeout);
794  }
795  }
796  }
797  LOG_DEBUG("exit robot trajectory update thread");
798  });
799 }
800 
801 RobotTrajectoryDisplay::~RobotTrajectoryDisplay() {
802  {
803  std::unique_lock<std::mutex> lock(_update_mutex);
804  _update_exit = true;
805  _update_condition.notify_all();
806  }
807  _update_thread.join();
808 }
809 
810 void RobotModelDisplay::renderSync(const RenderSyncContext &c) {
811  auto context = c;
812  context.pose.setIdentity();
813  _transformer = LockScope()->document()->display()->transformer;
814  if (_robot_state) {
815  for (size_t i = 0; i < _robot_state->robot_model->links.size(); i++) {
816  auto &link = _robot_state->robot_model->links.at(i);
817  if (auto transform = link->frame.pose(_transformer)) {
818  _robot_state->mesh_renderers.at(i)->pose((*transform) * link->pose);
819  _robot_state->mesh_renderers.at(i)->show();
820  } else {
821  _robot_state->mesh_renderers.at(i)->hide();
822  }
823  }
824  }
825  RobotDisplayBase::renderSync(context);
826 }
827 
828 void RobotModelDisplay::renderAsync(const RenderAsyncContext &context) {
829  RobotDisplayBase::renderAsync(context);
830 }
Definition: node.h:20
Definition: mesh.h:11