robotis_manipulator_common.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Authors: Darby Lim, Hye-Jong KIM, Ryan Shim, Yong-Ho Na */
18 
19 #include "../../include/robotis_manipulator/robotis_manipulator_common.h"
20 
21 using namespace robotis_manipulator;
22 
23 bool robotis_manipulator::setEffortToValue(std::vector<JointValue> *value, std::vector<double> effort)
24 {
25  if(value->size()==effort.size()){
26  for(int i=0; i<value->size(); i++){
27  value->at(i).effort=effort.at(i);
28  }
29  return true;
30  }
31  else{
32  return false;
33  }
34 }
35 
36 bool robotis_manipulator::setPositionToValue(std::vector<JointValue> *value, std::vector<double> position)
37 {
38  if(value->size()==position.size()){
39  for(int i=0; i<value->size(); i++){
40  value->at(i).position=position.at(i);
41  }
42  return true;
43  }
44  else{
45  return false;
46  }
47 }
48 
50 
51 /*****************************************************************************
52 ** Add Function
53 *****************************************************************************/
54 void Manipulator::addWorld(Name world_name,
55  Name child_name,
56  Eigen::Vector3d world_position,
57  Eigen::Matrix3d world_orientation)
58 {
59  world_.name = world_name;
60  world_.child = child_name;
61  world_.pose.kinematic.position = world_position;
62  world_.pose.kinematic.orientation = world_orientation;
63  world_.pose.dynamic.linear.velocity = Eigen::Vector3d::Zero();
64  world_.pose.dynamic.linear.acceleration = Eigen::Vector3d::Zero();
65  world_.pose.dynamic.angular.velocity = Eigen::Vector3d::Zero();
66  world_.pose.dynamic.angular.acceleration = Eigen::Vector3d::Zero();
67 }
68 
70  Name parent_name,
71  Name child_name,
72  Eigen::Vector3d relative_position,
73  Eigen::Matrix3d relative_orientation,
74  Eigen::Vector3d axis_of_rotation,
75  int8_t joint_actuator_id,
76  double max_position_limit,
77  double min_position_limit,
78  double coefficient,
79  double mass,
80  Eigen::Matrix3d inertia_tensor,
81  Eigen::Vector3d center_of_mass,
82  double torque_coefficient)
83 {
84  Component temp_component;
85  if (joint_actuator_id != -1)
86  {
87  dof_++;
88  temp_component.component_type = ACTIVE_JOINT_COMPONENT;
89  }
90  else
91  {
92  temp_component.component_type = PASSIVE_JOINT_COMPONENT;
93  }
94 
95  temp_component.name.parent = parent_name;
96  temp_component.name.child.push_back(child_name);
97  temp_component.relative.pose_from_parent.position = relative_position;
98  temp_component.relative.pose_from_parent.orientation = relative_orientation;
99  temp_component.relative.inertia.mass = mass;
100  temp_component.relative.inertia.inertia_tensor = inertia_tensor;
101  temp_component.relative.inertia.center_of_mass = center_of_mass;
102  temp_component.joint_constant.id = joint_actuator_id;
103  temp_component.joint_constant.coefficient = coefficient;
104  temp_component.joint_constant.axis = axis_of_rotation;
105  temp_component.joint_constant.position_limit.maximum = max_position_limit;
106  temp_component.joint_constant.position_limit.minimum = min_position_limit;
107  temp_component.joint_constant.torque_coefficient = torque_coefficient;
108 
109  temp_component.pose_from_world.kinematic.position = Eigen::Vector3d::Zero();
110  temp_component.pose_from_world.kinematic.orientation = Eigen::Matrix3d::Identity();
111  temp_component.pose_from_world.dynamic.linear.velocity = Eigen::Vector3d::Zero();
112  temp_component.pose_from_world.dynamic.linear.acceleration = Eigen::Vector3d::Zero();
113  temp_component.pose_from_world.dynamic.angular.velocity = Eigen::Vector3d::Zero();
114  temp_component.pose_from_world.dynamic.angular.acceleration = Eigen::Vector3d::Zero();
115 
116  temp_component.joint_value.position = 0.0;
117  temp_component.joint_value.velocity = 0.0;
118  temp_component.joint_value.effort = 0.0;
119 
120  component_.insert(std::make_pair(my_name, temp_component));
121 }
122 
124  Name parent_name,
125  Eigen::Vector3d relative_position,
126  Eigen::Matrix3d relative_orientation,
127  int8_t tool_id,
128  double max_position_limit,
129  double min_position_limit,
130  double coefficient,
131  double mass,
132  Eigen::Matrix3d inertia_tensor,
133  Eigen::Vector3d center_of_mass,
134  double torque_coefficient)
135 {
136  Component temp_component;
137 
138  temp_component.name.parent = parent_name;
139  temp_component.name.child.resize(0);
140  temp_component.component_type = TOOL_COMPONENT;
141  temp_component.relative.pose_from_parent.position = relative_position;
142  temp_component.relative.pose_from_parent.orientation = relative_orientation;
143  temp_component.relative.inertia.mass = mass;
144  temp_component.relative.inertia.inertia_tensor = inertia_tensor;
145  temp_component.relative.inertia.center_of_mass = center_of_mass;
146  temp_component.joint_constant.id = tool_id;
147  temp_component.joint_constant.coefficient = coefficient;
148  temp_component.joint_constant.axis = Eigen::Vector3d::Zero();
149  temp_component.joint_constant.position_limit.maximum = max_position_limit;
150  temp_component.joint_constant.position_limit.minimum = min_position_limit;
151  temp_component.joint_constant.torque_coefficient = torque_coefficient;
152 
153  temp_component.pose_from_world.kinematic.position = Eigen::Vector3d::Zero();
154  temp_component.pose_from_world.kinematic.orientation = Eigen::Matrix3d::Identity();
155  temp_component.pose_from_world.dynamic.linear.velocity = Eigen::Vector3d::Zero();
156  temp_component.pose_from_world.dynamic.linear.acceleration = Eigen::Vector3d::Zero();
157  temp_component.pose_from_world.dynamic.angular.velocity = Eigen::Vector3d::Zero();
158  temp_component.pose_from_world.dynamic.angular.acceleration = Eigen::Vector3d::Zero();
159 
160  temp_component.joint_value.position = 0.0;
161  temp_component.joint_value.velocity = 0.0;
162  temp_component.joint_value.effort = 0.0;
163 
164  component_.insert(std::make_pair(my_name, temp_component));
165 }
166 
167 void Manipulator::addComponentChild(Name my_name, Name child_name)
168 {
169  component_.at(my_name).name.child.push_back(child_name);
170 }
171 
173 {
174  log::println("----------<Manipulator Description>----------");
175  log::println("<Degree of Freedom>\n", dof_);
176  log::println("<Number of Components>\n", component_.size());
177  log::println("");
178  log::println("<World Configuration>");
179  log::println(" [Name]");
180  log::print(" -World Name : "); log::println(STRING(world_.name));
181  log::print(" -Child Name : "); log::println(STRING(world_.child));
182  log::println(" [Static Pose]");
183  log::println(" -Position : ");
185  log::println(" -Orientation : ");
187  log::println(" [Dynamic Pose]");
188  log::println(" -Linear Velocity : ");
190  log::println(" -Linear acceleration : ");
192  log::println(" -Angular Velocity : ");
194  log::println(" -Angular acceleration : ");
196 
197  std::vector<double> result_vector;
198  std::map<Name, Component>::iterator it_component;
199 
200  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
201  {
202  log::println("");
203  log::println("<"); log::print(STRING(it_component->first)); log::print("Configuration>");
204  if(component_.at(it_component->first).component_type == ACTIVE_JOINT_COMPONENT)
205  log::println(" [Component Type]\n Active Joint");
206  else if(component_.at(it_component->first).component_type == PASSIVE_JOINT_COMPONENT)
207  log::println(" [Component Type]\n Passive Joint");
208  else if(component_.at(it_component->first).component_type == TOOL_COMPONENT)
209  log::println(" [Component Type]\n Tool");
210  log::println(" [Name]");
211  log::print(" -Parent Name : "); log::println(STRING(component_.at(it_component->first).name.parent));
212  for(uint32_t index = 0; index < component_.at(it_component->first).name.child.size(); index++)
213  {
214  log::print(" -Child Name",index+1,0);
215  log::print(" : ");
216  log::println(STRING(component_.at(it_component->first).name.child.at(index)));
217  }
218  log::println(" [Actuator]");
219  log::print(" -Actuator Name : ");
220  log::println(STRING(component_.at(it_component->first).actuator_name));
221  log::print(" -ID : ");
222  log::println("", component_.at(it_component->first).joint_constant.id,0);
223  log::println(" -Joint Axis : ");
224  log::print_vector(component_.at(it_component->first).joint_constant.axis);
225  log::print(" -Coefficient : ");
226  log::println("", component_.at(it_component->first).joint_constant.coefficient);
227  log::println(" -Position Limit : ");
228  log::print(" Maximum :", component_.at(it_component->first).joint_constant.position_limit.maximum);
229  log::println(", Minimum :", component_.at(it_component->first).joint_constant.position_limit.minimum);
230 
231  log::println(" [Actuator Value]");
232  log::println(" -Position : ", component_.at(it_component->first).joint_value.position);
233  log::println(" -Velocity : ", component_.at(it_component->first).joint_value.velocity);
234  log::println(" -Acceleration : ", component_.at(it_component->first).joint_value.acceleration);
235  log::println(" -Effort : ", component_.at(it_component->first).joint_value.effort);
236 
237  log::println(" [Constant]");
238  log::println(" -Relative Position from parent component : ");
239  log::print_vector(component_.at(it_component->first).relative.pose_from_parent.position);
240  log::println(" -Relative Orientation from parent component : ");
241  log::print_matrix(component_.at(it_component->first).relative.pose_from_parent.orientation);
242  log::print(" -Mass : ");
243  log::println("", component_.at(it_component->first).relative.inertia.mass);
244  log::println(" -Inertia Tensor : ");
245  log::print_matrix(component_.at(it_component->first).relative.inertia.inertia_tensor);
246  log::println(" -Center of Mass : ");
247  log::print_vector(component_.at(it_component->first).relative.inertia.center_of_mass);
248 
249  log::println(" [Variable]");
250  log::println(" -Position : ");
251  log::print_vector(component_.at(it_component->first).pose_from_world.kinematic.position);
252  log::println(" -Orientation : ");
253  log::print_matrix(component_.at(it_component->first).pose_from_world.kinematic.orientation);
254  log::println(" -Linear Velocity : ");
255  log::print_vector(component_.at(it_component->first).pose_from_world.dynamic.linear.velocity);
256  log::println(" -Linear acceleration : ");
257  log::print_vector(component_.at(it_component->first).pose_from_world.dynamic.linear.acceleration);
258  log::println(" -Angular Velocity : ");
259  log::print_vector(component_.at(it_component->first).pose_from_world.dynamic.angular.velocity);
260  log::println(" -Angular acceleration : ");
261  log::print_vector(component_.at(it_component->first).pose_from_world.dynamic.angular.acceleration);
262  }
263  log::println("---------------------------------------------");
264 }
265 
266 
267 /*****************************************************************************
268 ** Set Function
269 *****************************************************************************/
270 void Manipulator::setTorqueCoefficient(Name component_name, double torque_coefficient)
271 {
272  component_.at(component_name).joint_constant.torque_coefficient = torque_coefficient;
273 }
274 
276 {
277  world_.pose = world_pose;
278 }
279 
281 {
282  world_.pose.kinematic = world_kinematic_pose;
283 }
284 
285 void Manipulator::setWorldPosition(Eigen::Vector3d world_position)
286 {
287  world_.pose.kinematic.position = world_position;
288 }
289 
290 void Manipulator::setWorldOrientation(Eigen::Matrix3d world_orientation)
291 {
292  world_.pose.kinematic.orientation = world_orientation;
293 }
294 
296 {
297  world_.pose.dynamic = world_dynamic_pose;
298 }
299 
300 void Manipulator::setWorldLinearVelocity(Eigen::Vector3d world_linear_velocity)
301 {
302  world_.pose.dynamic.linear.velocity = world_linear_velocity;
303 }
304 
305 void Manipulator::setWorldAngularVelocity(Eigen::Vector3d world_angular_velocity)
306 {
307  world_.pose.dynamic.angular.velocity = world_angular_velocity;
308 }
309 
310 void Manipulator::setWorldLinearAcceleration(Eigen::Vector3d world_linear_acceleration)
311 {
312  world_.pose.dynamic.linear.acceleration = world_linear_acceleration;
313 }
314 
315 void Manipulator::setWorldAngularAcceleration(Eigen::Vector3d world_angular_acceleration)
316 {
317  world_.pose.dynamic.angular.acceleration = world_angular_acceleration;
318 }
319 
320 void Manipulator::setComponent(Name component_name, Component component)
321 {
322  component_.at(component_name) = component;
323 }
324 
325 void Manipulator::setComponentActuatorName(Name component_name, Name actuator_name)
326 {
327  component_.at(component_name).actuator_name = actuator_name;
328 }
329 
330 void Manipulator::setComponentPoseFromWorld(Name component_name, Pose pose_to_world)
331 {
332  if (component_.find(component_name) != component_.end())
333  {
334  component_.at(component_name).pose_from_world = pose_to_world;
335  }
336  else
337  {
338  log::error("[setComponentPoseFromWorld] Wrong name.");
339  }
340 }
341 
343 {
344  if (component_.find(component_name) != component_.end())
345  {
346  component_.at(component_name).pose_from_world.kinematic = pose_to_world;
347  }
348  else
349  {
350  log::error("[setComponentKinematicPoseFromWorld] Wrong name.");
351  }
352 }
353 
354 void Manipulator::setComponentPositionFromWorld(Name component_name, Eigen::Vector3d position_to_world)
355 {
356  if (component_.find(component_name) != component_.end())
357  {
358  component_.at(component_name).pose_from_world.kinematic.position = position_to_world;
359  }
360  else
361  {
362  log::error("[setComponentPositionFromWorld] Wrong name.");
363  }
364 }
365 
366 void Manipulator::setComponentOrientationFromWorld(Name component_name, Eigen::Matrix3d orientation_to_wolrd)
367 {
368  if (component_.find(component_name) != component_.end())
369  {
370  component_.at(component_name).pose_from_world.kinematic.orientation = orientation_to_wolrd;
371  }
372  else
373  {
374  log::error("[setComponentOrientationFromWorld] Wrong name.");
375  }
376 }
377 
379 {
380  if (component_.find(component_name) != component_.end())
381  {
382  component_.at(component_name).pose_from_world.dynamic = dynamic_pose;
383  }
384  else
385  {
386  log::error("[setComponentDynamicPoseFromWorld] Wrong name.");
387  }
388 }
389 
390 void Manipulator::setJointPosition(Name component_name, double position)
391 {
392  component_.at(component_name).joint_value.position = position;
393 }
394 
395 void Manipulator::setJointVelocity(Name component_name, double velocity)
396 {
397  component_.at(component_name).joint_value.velocity = velocity;
398 }
399 
400 void Manipulator::setJointAcceleration(Name component_name, double acceleration)
401 {
402  component_.at(component_name).joint_value.acceleration = acceleration;
403 }
404 
405 void Manipulator::setJointEffort(Name component_name, double effort)
406 {
407  component_.at(component_name).joint_value.effort = effort;
408 }
409 
410 void Manipulator::setJointValue(Name component_name, JointValue joint_value)
411 {
412  component_.at(component_name).joint_value = joint_value;
413 }
414 
415 void Manipulator::setAllActiveJointPosition(std::vector<double> joint_position_vector)
416 {
417  int8_t index = 0;
418  std::map<Name, Component>::iterator it_component;
419 
420  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
421  {
422  if (component_.at(it_component->first).component_type == ACTIVE_JOINT_COMPONENT)
423  {
424  component_.at(it_component->first).joint_value.position = joint_position_vector.at(index);
425  index++;
426  }
427  }
428 }
429 
430 void Manipulator::setAllActiveJointValue(std::vector<JointValue> joint_value_vector)
431 {
432  int8_t index = 0;
433  std::map<Name, Component>::iterator it_component;
434 
435  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
436  {
437  if (component_.at(it_component->first).component_type == ACTIVE_JOINT_COMPONENT)
438  {
439  component_.at(it_component->first).joint_value.position = joint_value_vector.at(index).position;
440  component_.at(it_component->first).joint_value.velocity = joint_value_vector.at(index).velocity;
441  component_.at(it_component->first).joint_value.acceleration = joint_value_vector.at(index).acceleration;
442  component_.at(it_component->first).joint_value.effort = joint_value_vector.at(index).effort;
443  index++;
444  }
445  }
446 }
447 
448 void Manipulator::setAllJointPosition(std::vector<double> joint_position_vector)
449 {
450  int8_t index = 0;
451  std::map<Name, Component>::iterator it_component;
452 
453  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
454  {
455  if (component_.at(it_component->first).component_type == ACTIVE_JOINT_COMPONENT || component_.at(it_component->first).component_type == PASSIVE_JOINT_COMPONENT)
456  {
457  component_.at(it_component->first).joint_value.position = joint_position_vector.at(index);
458  index++;
459  }
460  }
461 }
462 
463 void Manipulator::setAllJointValue(std::vector<JointValue> joint_value_vector)
464 {
465  int8_t index = 0;
466  std::map<Name, Component>::iterator it_component;
467 
468  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
469  {
470  if (component_.at(it_component->first).component_type == ACTIVE_JOINT_COMPONENT || component_.at(it_component->first).component_type == PASSIVE_JOINT_COMPONENT)
471  {
472  component_.at(it_component->first).joint_value = joint_value_vector.at(index);
473  index++;
474  }
475  }
476 }
477 
478 void Manipulator::setAllToolPosition(std::vector<double> tool_position_vector)
479 {
480  int8_t index = 0;
481  std::map<Name, Component>::iterator it_component;
482 
483  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
484  {
485  if (component_.at(it_component->first).component_type == TOOL_COMPONENT)
486  {
487  component_.at(it_component->first).joint_value.position = tool_position_vector.at(index);
488  index++;
489  }
490  }
491 }
492 
493 void Manipulator::setAllToolValue(std::vector<JointValue> tool_value_vector)
494 {
495  int8_t index = 0;
496  std::map<Name, Component>::iterator it_component;
497 
498  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
499  {
500  if (component_.at(it_component->first).component_type == TOOL_COMPONENT)
501  {
502  component_.at(it_component->first).joint_value = tool_value_vector.at(index);
503  index++;
504  }
505  }
506 }
507 
508 
509 /*****************************************************************************
510 ** Get Function
511 *****************************************************************************/
513 {
514  return dof_;
515 }
516 
518 {
519  return world_.name;
520 }
521 
523 {
524  return world_.child;
525 }
526 
528 {
529  return world_.pose;
530 }
531 
533 {
534  return world_.pose.kinematic;
535 }
536 
538 {
539  return world_.pose.kinematic.position;
540 }
541 
543 {
545 }
546 
548 {
549  return world_.pose.dynamic;
550 }
551 
553 {
554  return component_.size();
555 }
556 
557 std::map<Name, Component> Manipulator::getAllComponent()
558 {
559  return component_;
560 }
561 
562 std::map<Name, Component>::iterator Manipulator::getIteratorBegin()
563 {
564  return component_.begin();
565 }
566 
567 std::map<Name, Component>::iterator Manipulator::getIteratorEnd()
568 {
569  return component_.end();;
570 }
571 
573 {
574  return component_.at(component_name);
575 }
576 
578 {
579  return component_.at(component_name).actuator_name;
580 }
581 
583 {
584  return component_.at(component_name).name.parent;
585 }
586 
587 std::vector<Name> Manipulator::getComponentChildName(Name component_name)
588 {
589  return component_.at(component_name).name.child;
590 }
591 
593 {
594  return component_.at(component_name).pose_from_world;
595 }
596 
598 {
599  return component_.at(component_name).pose_from_world.kinematic;
600 }
601 
602 Eigen::Vector3d Manipulator::getComponentPositionFromWorld(Name component_name)
603 {
604  return component_.at(component_name).pose_from_world.kinematic.position;
605 }
606 
608 {
609  return component_.at(component_name).pose_from_world.kinematic.orientation;
610 }
611 
613 {
614  return component_.at(component_name).pose_from_world.dynamic;
615 }
616 
618 {
619  return component_.at(component_name).relative.pose_from_parent;
620 }
621 
623 {
624  return component_.at(component_name).relative.pose_from_parent.position;
625 }
626 
628 {
629  return component_.at(component_name).relative.pose_from_parent.orientation;
630 }
631 
632 int8_t Manipulator::getId(Name component_name)
633 {
634  return component_.at(component_name).joint_constant.id;
635 }
636 
637 double Manipulator::getCoefficient(Name component_name)
638 {
639  return component_.at(component_name).joint_constant.coefficient;
640 }
641 
643 {
644  return component_.at(component_name).joint_constant.torque_coefficient;
645 }
646 
647 Eigen::Vector3d Manipulator::getAxis(Name component_name)
648 {
649  return component_.at(component_name).joint_constant.axis;
650 }
651 
652 double Manipulator::getJointPosition(Name component_name)
653 {
654  return component_.at(component_name).joint_value.position;
655 }
656 
657 double Manipulator::getJointVelocity(Name component_name)
658 {
659  return component_.at(component_name).joint_value.velocity;
660 }
661 
663 {
664  return component_.at(component_name).joint_value.acceleration;
665 }
666 
667 double Manipulator::getJointEffort(Name component_name)
668 {
669  return component_.at(component_name).joint_value.effort;
670 }
671 
673 {
674  return component_.at(component_name).joint_value;
675 }
676 
677 double Manipulator::getComponentMass(Name component_name)
678 {
679  return component_.at(component_name).relative.inertia.mass;
680 }
681 
682 Eigen::Matrix3d Manipulator::getComponentInertiaTensor(Name component_name)
683 {
684  return component_.at(component_name).relative.inertia.inertia_tensor;
685 }
686 
687 Eigen::Vector3d Manipulator::getComponentCenterOfMass(Name component_name)
688 {
689  return component_.at(component_name).relative.inertia.center_of_mass;
690 }
691 
692 std::vector<double> Manipulator::getAllJointPosition()
693 {
694  std::vector<double> result_vector;
695  std::map<Name, Component>::iterator it_component;
696 
697  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
698  {
699  if (checkComponentType(it_component->first, ACTIVE_JOINT_COMPONENT) || checkComponentType(it_component->first, PASSIVE_JOINT_COMPONENT))
700  {
701  result_vector.push_back(component_.at(it_component->first).joint_value.position);
702  }
703  }
704  return result_vector;
705 }
706 
707 std::vector<JointValue> Manipulator::getAllJointValue()
708 {
709  std::vector<JointValue> result_vector;
710  std::map<Name, Component>::iterator it_component;
711 
712  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
713  {
714  if (checkComponentType(it_component->first, ACTIVE_JOINT_COMPONENT) || checkComponentType(it_component->first, PASSIVE_JOINT_COMPONENT))
715  {
716  result_vector.push_back(component_.at(it_component->first).joint_value);
717  }
718  }
719  return result_vector;
720 }
721 
723 {
724  std::vector<double> result_vector;
725  std::map<Name, Component>::iterator it_component;
726 
727  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
728  {
729  if (checkComponentType(it_component->first, ACTIVE_JOINT_COMPONENT))
730  {
731  result_vector.push_back(component_.at(it_component->first).joint_value.position);
732  }
733  }
734  return result_vector;
735 }
736 
737 std::vector<JointValue> Manipulator::getAllActiveJointValue()
738 {
739  std::vector<JointValue> result_vector;
740  std::map<Name, Component>::iterator it_component;
741 
742  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
743  {
744  if (checkComponentType(it_component->first, ACTIVE_JOINT_COMPONENT))
745  {
746  result_vector.push_back(component_.at(it_component->first).joint_value);
747  }
748  }
749  return result_vector;
750 }
751 
752 std::vector<double> Manipulator::getAllToolPosition()
753 {
754  std::vector<double> result_vector;
755  std::map<Name, Component>::iterator it_component;
756 
757  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
758  {
759  if (checkComponentType(it_component->first, TOOL_COMPONENT))
760  {
761  result_vector.push_back(component_.at(it_component->first).joint_value.position);
762  }
763  }
764  return result_vector;
765 }
766 
767 
768 std::vector<JointValue> Manipulator::getAllToolValue()
769 {
770  std::vector<JointValue> result_vector;
771  std::map<Name, Component>::iterator it_component;
772 
773  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
774  {
775  if (checkComponentType(it_component->first, TOOL_COMPONENT))
776  {
777  result_vector.push_back(component_.at(it_component->first).joint_value);
778  }
779  }
780  return result_vector;
781 }
782 
783 std::vector<uint8_t> Manipulator::getAllJointID()
784 {
785  std::vector<uint8_t> joint_id;
786  std::map<Name, Component>::iterator it_component;
787 
788  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
789  {
790  if (checkComponentType(it_component->first, ACTIVE_JOINT_COMPONENT) || checkComponentType(it_component->first, PASSIVE_JOINT_COMPONENT))
791  {
792  joint_id.push_back(component_.at(it_component->first).joint_constant.id);
793  }
794  }
795  return joint_id;
796 }
797 
798 std::vector<uint8_t> Manipulator::getAllActiveJointID()
799 {
800  std::vector<uint8_t> active_joint_id;
801  std::map<Name, Component>::iterator it_component;
802 
803  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
804  {
805  if (checkComponentType(it_component->first, ACTIVE_JOINT_COMPONENT))
806  {
807  active_joint_id.push_back(component_.at(it_component->first).joint_constant.id);
808  }
809  }
810  return active_joint_id;
811 }
812 
813 
815 {
816  std::vector<Name> tool_name;
817  std::map<Name, Component>::iterator it_component;
818 
819  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
820  {
821  if (checkComponentType(it_component->first, TOOL_COMPONENT))
822  {
823  tool_name.push_back(it_component->first);
824  }
825  }
826  return tool_name;
827 }
828 
830 {
831  std::vector<Name> active_joint_name;
832  std::map<Name, Component>::iterator it_component;
833 
834  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
835  {
836  if (checkComponentType(it_component->first, ACTIVE_JOINT_COMPONENT))
837  {
838  active_joint_name.push_back(it_component->first);
839  }
840  }
841  return active_joint_name;
842 }
843 
844 
845 /*****************************************************************************
846 ** Check Function
847 *****************************************************************************/
848 bool Manipulator::checkJointLimit(Name component_name, double value)
849 {
850  if(component_.at(component_name).joint_constant.position_limit.maximum < value)
851  return false;
852  else if(component_.at(component_name).joint_constant.position_limit.minimum > value)
853  return false;
854  else
855  return true;
856 }
857 
858 bool Manipulator::checkComponentType(Name component_name, ComponentType component_type)
859 {
860  if(component_.at(component_name).component_type == component_type)
861  return true;
862  else
863  return false;
864 }
865 
866 
867 /*****************************************************************************
868 ** Find Function
869 *****************************************************************************/
871 {
872  std::map<Name, Component>::iterator it_component;
873 
874  for (it_component = component_.begin(); it_component != component_.end(); it_component++)
875  {
876  if (component_.at(it_component->first).joint_constant.id == id)
877  {
878  return it_component->first;
879  }
880  }
881  return {};
882 }
double getJointPosition(Name component_name)
void setComponentActuatorName(Name component_name, Name actuator_name)
std::vector< JointValue > getAllJointValue()
std::map< Name, Component >::iterator getIteratorEnd()
void setWorldOrientation(Eigen::Matrix3d world_orientation)
Pose getComponentPoseFromWorld(Name component_name)
void addWorld(Name world_name, Name child_name, Eigen::Vector3d world_position=Eigen::Vector3d::Zero(), Eigen::Matrix3d world_orientation=Eigen::Matrix3d::Identity())
JointValue getJointValue(Name component_name)
void setAllActiveJointPosition(std::vector< double > joint_position_vector)
void setComponentOrientationFromWorld(Name component_name, Eigen::Matrix3d orientation_to_wolrd)
std::map< Name, Component > getAllComponent()
Eigen::Matrix3d getComponentRelativeOrientationFromParent(Name component_name)
Eigen::Matrix3d getComponentOrientationFromWorld(Name component_name)
bool checkComponentType(Name component_name, ComponentType component_type)
Eigen::Vector3d getAxis(Name component_name)
double getJointAcceleration(Name component_name)
bool setEffortToValue(std::vector< JointValue > *value, std::vector< double > effort)
Eigen::Vector3d getComponentRelativePositionFromParent(Name component_name)
void setAllToolPosition(std::vector< double > tool_position_vector)
void setWorldAngularVelocity(Eigen::Vector3d world_angular_velocity)
Name getComponentParentName(Name component_name)
void setComponent(Name component_name, Component component)
bool checkJointLimit(Name Component_name, double value)
void setAllJointPosition(std::vector< double > joint_position_vector)
void setWorldPosition(Eigen::Vector3d world_position)
void setJointAcceleration(Name name, double acceleration)
void setWorldLinearAcceleration(Eigen::Vector3d world_linear_acceleration)
Name getComponentActuatorName(Name component_name)
void setAllActiveJointValue(std::vector< JointValue > joint_value_vector)
void println(STRING str, STRING color="DEFAULT")
void setJointPosition(Name name, double position)
std::vector< JointValue > getAllActiveJointValue()
void setComponentPositionFromWorld(Name component_name, Eigen::Vector3d position_to_world)
KinematicPose getComponentRelativePoseFromParent(Name component_name)
DynamicPose getComponentDynamicPoseFromWorld(Name component_name)
double getTorqueCoefficient(Name component_name)
void setTorqueCoefficient(Name component_name, double torque_coefficient)
void setComponentPoseFromWorld(Name component_name, Pose pose_to_world)
void print_vector(std::vector< T > &vec, uint8_t decimal_point=3)
void setComponentDynamicPoseFromWorld(Name component_name, DynamicPose dynamic_pose)
std::vector< Name > getComponentChildName(Name component_name)
enum robotis_manipulator::_ComponentType ComponentType
void setAllJointValue(std::vector< JointValue > joint_value_vector)
void print(STRING str, STRING color="DEFAULT")
void setJointEffort(Name name, double effort)
void setJointVelocity(Name name, double velocity)
void addJoint(Name my_name, Name parent_name, Name child_name, Eigen::Vector3d relative_position, Eigen::Matrix3d relative_orientation, Eigen::Vector3d axis_of_rotation=Eigen::Vector3d::Zero(), int8_t joint_actuator_id=-1, double max_position_limit=M_PI, double min_position_limit=-M_PI, double coefficient=1.0, double mass=0.0, Eigen::Matrix3d inertia_tensor=Eigen::Matrix3d::Identity(), Eigen::Vector3d center_of_mass=Eigen::Vector3d::Zero(), double torque_coefficient=1.0)
void setJointValue(Name name, JointValue joint_value)
void setWorldAngularAcceleration(Eigen::Vector3d world_angular_acceleration)
double getJointVelocity(Name component_name)
Eigen::Vector3d getComponentPositionFromWorld(Name component_name)
void addComponentChild(Name my_name, Name child_name)
void setComponentKinematicPoseFromWorld(Name component_name, KinematicPose pose_to_world)
double getComponentMass(Name component_name)
bool setPositionToValue(std::vector< JointValue > *value, std::vector< double > position)
KinematicPose getComponentKinematicPoseFromWorld(Name component_name)
Eigen::Vector3d getComponentCenterOfMass(Name component_name)
void setAllToolValue(std::vector< JointValue > tool_value_vector)
std::map< Name, Component >::iterator getIteratorBegin()
Eigen::Matrix3d getComponentInertiaTensor(Name component_name)
void setWorldKinematicPose(KinematicPose world_kinematic_pose)
std::string STRING
void addTool(Name my_name, Name parent_name, Eigen::Vector3d relative_position, Eigen::Matrix3d relative_orientation, int8_t tool_id=-1, double max_position_limit=M_PI, double min_position_limit=-M_PI, double coefficient=1.0, double mass=0.0, Eigen::Matrix3d inertia_tensor=Eigen::Matrix3d::Identity(), Eigen::Vector3d center_of_mass=Eigen::Vector3d::Zero(), double torque_coefficient=1.0)
void print_matrix(matrix &m, uint8_t decimal_point=3)
void setWorldDynamicPose(DynamicPose world_dynamic_pose)
Component getComponent(Name component_name)
void setWorldLinearVelocity(Eigen::Vector3d world_linear_velocity)


robotis_manipulator
Author(s): Hye-Jong KIM , Darby Lim , Yong-Ho Na , Ryan Shim
autogenerated on Sat Oct 3 2020 03:14:51