robotis_manipulator.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.h"
20 
21 using namespace robotis_manipulator;
22 
23 
24 /*****************************************************************************
25 ** Constructor and Destructor
26 *****************************************************************************/
28 {
29  moving_state_ = false;
30  moving_fail_flag_ = false;
33  step_moving_state_ = false;
37 }
38 
40 
41 
42 /*****************************************************************************
43 ** Initialize Function
44 *****************************************************************************/
46  Name child_name,
47  Eigen::Vector3d world_position,
48  Eigen::Matrix3d world_orientation)
49 {
50  manipulator_.addWorld(world_name, child_name, world_position, world_orientation);
51 }
52 
54  Name parent_name,
55  Name child_name,
56  Eigen::Vector3d relative_position,
57  Eigen::Matrix3d relative_orientation,
58  Eigen::Vector3d axis_of_rotation,
59  int8_t joint_actuator_id,
60  double max_position_limit,
61  double min_position_limit,
62  double coefficient,
63  double mass,
64  Eigen::Matrix3d inertia_tensor,
65  Eigen::Vector3d center_of_mass,
66  double torque_coefficient)
67 {
68  manipulator_.addJoint(my_name, parent_name, child_name,
69  relative_position, relative_orientation, axis_of_rotation, joint_actuator_id,
70  max_position_limit, min_position_limit, coefficient, mass,
71  inertia_tensor, center_of_mass, torque_coefficient);
72 }
73 
75 {
76  manipulator_.addComponentChild(my_name, child_name);
77 }
78 
80  Name parent_name,
81  Eigen::Vector3d relative_position,
82  Eigen::Matrix3d relative_orientation,
83  int8_t tool_id,
84  double max_position_limit,
85  double min_position_limit,
86  double coefficient,
87  double object_mass,
88  Eigen::Matrix3d object_inertia_tensor,
89  Eigen::Vector3d object_center_of_mass)
90 {
91  manipulator_.addTool(my_name, parent_name,
92  relative_position, relative_orientation, tool_id,
93  max_position_limit, min_position_limit, coefficient, object_mass,
94  object_inertia_tensor, object_center_of_mass);
95 }
96 
98 {
100 }
101 
103 {
104  kinematics_= kinematics;
106 }
107 
109 {
110  dynamics_ = dynamics;
112 }
113 
114 void RobotisManipulator::addJointActuator(Name actuator_name, JointActuator *joint_actuator, std::vector<uint8_t> id_array, const void *arg)
115 {
116  joint_actuator_.insert(std::make_pair(actuator_name, joint_actuator));
117  if(joint_actuator_.find(actuator_name) != joint_actuator_.end())
118  {
119  joint_actuator_.at(actuator_name)->init(id_array, arg);
120  }
121  else
122  {
123  //error
124  }
125  for(uint32_t index = 0; index < id_array.size(); index++)
126  {
127  manipulator_.setComponentActuatorName(manipulator_.findComponentNameUsingId(static_cast<int8_t>(id_array.at(index))),actuator_name);
128  }
130 }
131 
132 void RobotisManipulator::addToolActuator(Name actuator_name, ToolActuator *tool_actuator, uint8_t id, const void *arg)
133 {
134  tool_actuator_.insert(std::make_pair(actuator_name, tool_actuator));
135  if(tool_actuator_.find(actuator_name) != tool_actuator_.end())
136  {
137  tool_actuator_.at(actuator_name)->init(id, arg);
138  }
139  else
140  {
141  //error
142  }
143  manipulator_.setComponentActuatorName(manipulator_.findComponentNameUsingId(static_cast<int8_t>(id)), actuator_name);
145 }
146 
147 void RobotisManipulator::addCustomTrajectory(Name trajectory_name, CustomJointTrajectory *custom_trajectory)
148 {
149  trajectory_.addCustomTrajectory(trajectory_name, custom_trajectory);
150 }
151 
152 void RobotisManipulator::addCustomTrajectory(Name trajectory_name, CustomTaskTrajectory *custom_trajectory)
153 {
154  trajectory_.addCustomTrajectory(trajectory_name, custom_trajectory);
155 }
156 
157 
158 /*****************************************************************************
159 ** Manipulator Function
160 *************************************trajectory_name****************************************/
162 {
163  return &manipulator_;
164 }
165 
166 void RobotisManipulator::setTorqueCoefficient(Name component_name, double torque_coefficient)
167 {
168  return manipulator_.setTorqueCoefficient(component_name, torque_coefficient);
169 }
170 
172 {
173  return manipulator_.getJointValue(joint_name);
174 }
175 
177 {
178  return manipulator_.getJointValue(tool_name);
179 }
180 
182 {
184 }
185 
186 std::vector<JointValue> RobotisManipulator::getAllJointValue()
187 {
189 }
190 
192 {
194 }
195 
196 std::vector<JointValue> RobotisManipulator::getAllToolValue()
197 {
198  return manipulator_.getAllToolValue();
199 }
200 
202 {
203  return manipulator_.getComponentKinematicPoseFromWorld(component_name);
204 }
205 
207 {
208  return manipulator_.getComponentDynamicPoseFromWorld(component_name);
209 }
210 
212 {
213  return manipulator_.getComponentPoseFromWorld(component_name);
214 }
215 
217 {
218  return kinematics_;
219 }
220 
221 
222 /*****************************************************************************
223 ** Kinematics Function (Including Virtual Function)
224 *****************************************************************************/
225 Eigen::MatrixXd RobotisManipulator::jacobian(Name tool_name)
226 {
228  return kinematics_->jacobian(&manipulator_, tool_name);
229  }
230  else{
231  log::warn("[jacobian] Kinematics Class was not added.");
232  return Eigen::MatrixXd::Identity(manipulator_.getDOF(),manipulator_.getDOF());
233  }
234 }
235 
237 {
240  }
241  else{
242  log::warn("[solveForwardKinematics] Kinematics Class was not added.");
243  }
244 }
245 
246 void RobotisManipulator::solveForwardKinematics(std::vector<JointValue> *goal_joint_value)
247 {
249  Manipulator temp_manipulator = manipulator_;
250  temp_manipulator.setAllActiveJointValue(*goal_joint_value);
251  kinematics_->solveForwardKinematics(&temp_manipulator);
252  *goal_joint_value = temp_manipulator.getAllActiveJointValue();
253  }
254  else{
255  log::warn("[solveForwardKinematics] Kinematics Class was not added.");
256  }
257 }
258 
259 bool RobotisManipulator::solveInverseKinematics(Name tool_name, Pose goal_pose, std::vector<JointValue>* goal_joint_value)
260 {
262  return kinematics_->solveInverseKinematics(&manipulator_, tool_name, goal_pose, goal_joint_value);
263  }
264  else{
265  log::warn("[solveInverseKinematics] Kinematics Class was not added.");
266  return false;
267  }
268 }
269 
271 {
273  kinematics_->setOption(arg);
274  }
275  else{
276  log::warn("[setKinematicsOption] Kinematics Class was not added.");
277  }
278 }
279 
281 {
282  return dynamics_;
283 }
284 
285 
286 /*****************************************************************************
287 ** Dynamics Function (Including Virtual Function)
288 *****************************************************************************/
289 void RobotisManipulator::solveForwardDynamics(std::map<Name, double> joint_torque)
290 {
293  }
294  else{
295  log::warn("[solveForwardDynamics] Dynamics Class was not added.");
296  }
297 }
298 
299 bool RobotisManipulator::solveInverseDynamics(std::map<Name, double> *joint_torque)
300 {
302  return dynamics_->solveInverseDynamics(manipulator_, joint_torque);
303  }
304  else{
305  log::warn("[solveInverseDynamics] Dynamics Class was not added.");
306  return false;
307  }
308 }
309 
310 bool RobotisManipulator::solveGravityTerm(std::map<Name, double> *joint_torque)
311 {
313  Manipulator temp_manipulator = manipulator_;
314  std::vector<JointValue> present_joint_value = temp_manipulator.getAllActiveJointValue();
315  present_joint_value = trajectory_.removeWaypointDynamicData(present_joint_value);
316  temp_manipulator.setAllActiveJointValue(present_joint_value);
317  kinematics_->solveForwardKinematics(&temp_manipulator);
318  return dynamics_->solveInverseDynamics(temp_manipulator, joint_torque);
319  }
320  else{
321  log::warn("[solveInverseDynamics] Dynamics Class was not added.");
322  return false;
323  }
324 }
325 
326 void RobotisManipulator::setDynamicsOption(STRING param_name, const void* arg)
327 {
329  dynamics_->setOption(param_name, arg);
330  }
331  else{
332  log::warn("[setDynamicsOption] Dynamics Class was not added.");
333  }
334 }
335 
336 void RobotisManipulator::setDynamicsEnvironments(STRING param_name, const void* arg)
337 {
339  dynamics_->setEnvironments(param_name, arg);
340  }
341  else{
342  log::warn("[setDynamicsEnvironments] Dynamics Class was not added.");
343  }
344 }
345 
347 {
348  return joint_actuator_.at(actuator_name);
349 }
350 
352 {
353  return tool_actuator_.at(actuator_name);
354 }
355 
356 /*****************************************************************************
357 ** Actuator Function (Including Virtual Function)
358 *****************************************************************************/
359 void RobotisManipulator::setJointActuatorMode(Name actuator_name, std::vector<uint8_t> id_array, const void *arg)
360 {
362  {
363  if(joint_actuator_.find(actuator_name) != joint_actuator_.end())
364  {
365  joint_actuator_.at(actuator_name)->setMode(id_array, arg);
366  }
367  else
368  {
369  robotis_manipulator::log::error("[jointActuatorSetMode] Worng Actuator Name.");
370  }
371  }
372 }
373 
374 void RobotisManipulator::setToolActuatorMode(Name actuator_name, const void *arg)
375 {
377  {
378  if(tool_actuator_.find(actuator_name) != tool_actuator_.end())
379  {
380  tool_actuator_.at(actuator_name)->setMode(arg);
381  }
382  else
383  {
384  robotis_manipulator::log::error("[setToolActuatorMode] Worng Actuator Name.");
385  }
386  }
387 }
388 
389 std::vector<uint8_t> RobotisManipulator::getJointActuatorId(Name actuator_name)
390 {
392  {
393  if(joint_actuator_.find(actuator_name) != joint_actuator_.end())
394  {
395  return joint_actuator_.at(actuator_name)->getId();
396  }
397  else
398  {
399  robotis_manipulator::log::error("[getJointActuatorId] Worng Actuator Name.");
400  }
401  }
402  return {};
403 }
404 
406 {
408  {
409  if(tool_actuator_.find(actuator_name) != tool_actuator_.end())
410  {
411  return tool_actuator_.at(actuator_name)->getId();
412  }
413  else
414  {
415  robotis_manipulator::log::error("[getToolActuatorId] Worng Actuator Name.");
416  }
417  }
418  return {};
419 }
420 
422 {
424  {
425  if(joint_actuator_.find(actuator_name) != joint_actuator_.end())
426  {
427  joint_actuator_.at(actuator_name)->enable();
428  }
429  else if(tool_actuator_.find(actuator_name) != tool_actuator_.end())
430  {
431  tool_actuator_.at(actuator_name)->enable();
432  }
433  else
434  {
435  robotis_manipulator::log::error("[enableActuator] Worng Actuator Name.");
436  }
437  }
439 }
440 
442 {
444  {
445  if(joint_actuator_.find(actuator_name) != joint_actuator_.end())
446  {
447  joint_actuator_.at(actuator_name)->disable();
448  }
449  else if(tool_actuator_.find(actuator_name) != tool_actuator_.end())
450  {
451  tool_actuator_.at(actuator_name)->disable();
452  }
453  else
454  {
455  robotis_manipulator::log::error("[disableActuator] Worng Actuator Name.");
456  }
457  }
458 }
459 
461 {
463  {
464  std::map<Name, JointActuator *>::iterator it_joint_actuator;
465  for(it_joint_actuator = joint_actuator_.begin(); it_joint_actuator != joint_actuator_.end(); it_joint_actuator++)
466  {
467  joint_actuator_.at(it_joint_actuator->first)->enable();
468  }
469  }
471 }
472 
474 {
476  {
477  std::map<Name, JointActuator *>::iterator it_joint_actuator;
478  for(it_joint_actuator = joint_actuator_.begin(); it_joint_actuator != joint_actuator_.end(); it_joint_actuator++)
479  {
480  joint_actuator_.at(it_joint_actuator->first)->disable();
481  }
482  }
483 }
484 
486 {
488  {
489  std::map<Name, ToolActuator *>::iterator it_tool_actuator;
490  for(it_tool_actuator = tool_actuator_.begin(); it_tool_actuator != tool_actuator_.end(); it_tool_actuator++)
491  {
492  tool_actuator_.at(it_tool_actuator->first)->enable();
493  }
494  }
496 }
497 
499 {
501  {
502  std::map<Name, ToolActuator *>::iterator it_tool_actuator;
503  for(it_tool_actuator = tool_actuator_.begin(); it_tool_actuator != tool_actuator_.end(); it_tool_actuator++)
504  {
505  tool_actuator_.at(it_tool_actuator->first)->disable();
506  }
507  }
508 }
509 
511 {
513  {
514  std::map<Name, JointActuator *>::iterator it_joint_actuator;
515  for(it_joint_actuator = joint_actuator_.begin(); it_joint_actuator != joint_actuator_.end(); it_joint_actuator++)
516  {
517  joint_actuator_.at(it_joint_actuator->first)->enable();
518  }
519  std::map<Name, ToolActuator *>::iterator it_tool_actuator;
520  for(it_tool_actuator = tool_actuator_.begin(); it_tool_actuator != tool_actuator_.end(); it_tool_actuator++)
521  {
522  tool_actuator_.at(it_tool_actuator->first)->enable();
523  }
524  }
526 }
527 
529 {
531  {
532  std::map<Name, JointActuator *>::iterator it_joint_actuator;
533  for(it_joint_actuator = joint_actuator_.begin(); it_joint_actuator != joint_actuator_.end(); it_joint_actuator++)
534  {
535  joint_actuator_.at(it_joint_actuator->first)->disable();
536  }
537  std::map<Name, ToolActuator *>::iterator it_tool_actuator;
538  for(it_tool_actuator = tool_actuator_.begin(); it_tool_actuator != tool_actuator_.end(); it_tool_actuator++)
539  {
540  tool_actuator_.at(it_tool_actuator->first)->disable();
541  }
542  }
543 }
544 
546 {
548  {
549  if(joint_actuator_.find(actuator_name) != joint_actuator_.end())
550  {
551  return joint_actuator_.at(actuator_name)->getEnabledState();
552  }
553  else if(tool_actuator_.find(actuator_name) != tool_actuator_.end())
554  {
555  return tool_actuator_.at(actuator_name)->getEnabledState();
556  }
557  else
558  {
559  return {};
560  }
561  }
562  return {};
563 }
564 
566 {
568  {
569  double coefficient = manipulator_.getCoefficient(joint_component_name);
570  double torque_coefficient = manipulator_.getTorqueCoefficient(joint_component_name);
571  value.position = value.position / coefficient;
572  value.velocity = value.velocity / coefficient;
573  value.acceleration = value.acceleration / coefficient;
574  value.effort = value.effort / torque_coefficient;
575 
576  std::vector<uint8_t> id;
577  std::vector<JointValue> value_vector;
578  id.push_back(static_cast<uint8_t>(manipulator_.getId(joint_component_name)));
579  value_vector.push_back(value);
580 
581  //send to actuator
582  return joint_actuator_.at(manipulator_.getComponentActuatorName(joint_component_name))->sendJointActuatorValue(id, value_vector);
583  }
584  else
585  {
586  manipulator_.setJointValue(joint_component_name, value);
587  return true;
588  }
589 }
590 
591 bool RobotisManipulator::sendMultipleJointActuatorValue(std::vector<Name> joint_component_name, std::vector<JointValue> value_vector)
592 {
593  if(joint_component_name.size() != value_vector.size())
594  return false; //error;
595 
597  {
598  std::vector<int8_t> joint_id;
599  for(uint32_t index = 0; index < value_vector.size(); index++)
600  {
601  double coefficient = manipulator_.getCoefficient(joint_component_name.at(index));
602  double torque_coefficient = manipulator_.getTorqueCoefficient(joint_component_name.at(index));
603  value_vector.at(index).position = value_vector.at(index).position / coefficient;
604  value_vector.at(index).velocity = value_vector.at(index).velocity / coefficient;
605  value_vector.at(index).acceleration = value_vector.at(index).acceleration / coefficient;
606  value_vector.at(index).effort = value_vector.at(index).effort / torque_coefficient;
607  joint_id.push_back(manipulator_.getId(joint_component_name.at(index)));
608  }
609 
610  std::vector<uint8_t> single_actuator_id;
611  std::vector<JointValue> single_value_vector;
612  std::map<Name, JointActuator *>::iterator it_joint_actuator;
613  for(it_joint_actuator = joint_actuator_.begin(); it_joint_actuator != joint_actuator_.end(); it_joint_actuator++)
614  {
615  single_actuator_id = joint_actuator_.at(it_joint_actuator->first)->getId();
616  for(uint32_t index = 0; index < single_actuator_id.size(); index++)
617  {
618  for(uint32_t index2=0; index2 < joint_id.size(); index2++)
619  {
620  if(single_actuator_id.at(index) == joint_id.at(index2))
621  {
622  single_value_vector.push_back(value_vector.at(index2));
623  }
624  }
625  }
626  joint_actuator_.at(it_joint_actuator->first)->sendJointActuatorValue(single_actuator_id, single_value_vector);
627  }
628  return true;
629  }
630  else
631  {
632  //set to manipulator
633  for(uint8_t index = 0; index < joint_component_name.size(); index++)
634  manipulator_.setJointValue(joint_component_name.at(index), value_vector.at(index));
635  return true;
636  }
637 }
638 
639 bool RobotisManipulator::sendAllJointActuatorValue(std::vector<JointValue> value_vector)
640 {
642  {
643  std::map<Name, Component>::iterator it;
644  std::vector<int8_t> joint_id;
645  size_t index = 0;
646  for (it = manipulator_.getIteratorBegin(); it != manipulator_.getIteratorEnd(); it++)
647  {
649  {
650  double coefficient = manipulator_.getCoefficient(it->first);
651  double torque_coefficient = manipulator_.getTorqueCoefficient(it->first);
652  value_vector.at(index).position = value_vector.at(index).position / coefficient;
653  value_vector.at(index).velocity = value_vector.at(index).velocity / coefficient;
654  value_vector.at(index).acceleration = value_vector.at(index).acceleration / coefficient;
655  value_vector.at(index).effort = value_vector.at(index).effort / torque_coefficient;
656  joint_id.push_back(manipulator_.getId(it->first));
657  index++;
658  }
659  }
660 
661  std::vector<uint8_t> single_actuator_id;
662  std::vector<JointValue> single_value_vector;
663  std::map<Name, JointActuator *>::iterator it_joint_actuator;
664  for(it_joint_actuator = joint_actuator_.begin(); it_joint_actuator != joint_actuator_.end(); it_joint_actuator++)
665  {
666  single_actuator_id = joint_actuator_.at(it_joint_actuator->first)->getId();
667  for(uint32_t index = 0; index < single_actuator_id.size(); index++)
668  {
669  for(uint32_t index2=0; index2 < joint_id.size(); index2++)
670  {
671  if(single_actuator_id.at(index) == joint_id.at(index2))
672  {
673  single_value_vector.push_back(value_vector.at(index2));
674  }
675  }
676  }
677  joint_actuator_.at(it_joint_actuator->first)->sendJointActuatorValue(single_actuator_id, single_value_vector);
678  }
679  return true;
680  }
681  else
682  {
683  //set to manipulator
684  manipulator_.setAllActiveJointValue(value_vector);
685  }
686  return false;
687 }
688 
690 {
692  {
693  std::vector<uint8_t> actuator_id;
694  std::vector<JointValue> result;
695 
696  actuator_id.push_back(static_cast<uint8_t>(manipulator_.getId(joint_component_name)));
697 
698  result = joint_actuator_.at(manipulator_.getComponentActuatorName(joint_component_name))->receiveJointActuatorValue(actuator_id);
699 
700  double coefficient = manipulator_.getCoefficient(joint_component_name);
701  double torque_coefficient = manipulator_.getTorqueCoefficient(joint_component_name);
702  result.at(0).position = result.at(0).position * coefficient;
703  result.at(0).velocity = result.at(0).velocity * coefficient;
704  result.at(0).acceleration = result.at(0).acceleration * coefficient;
705  result.at(0).effort = result.at(0).effort * torque_coefficient;
706 
707  manipulator_.setJointValue(joint_component_name, result.at(0));
708  return result.at(0);
709  }
710  return {};
711 }
712 
713 std::vector<JointValue> RobotisManipulator::receiveMultipleJointActuatorValue(std::vector<Name> joint_component_name)
714 {
716  {
717  std::vector<JointValue> get_value_vector;
718  std::vector<uint8_t> get_actuator_id;
719 
720  std::vector<JointValue> single_value_vector;
721  std::vector<uint8_t> single_actuator_id;
722  std::map<Name, JointActuator *>::iterator it_joint_actuator;
723  for(it_joint_actuator = joint_actuator_.begin(); it_joint_actuator != joint_actuator_.end(); it_joint_actuator++)
724  {
725  single_actuator_id = joint_actuator_.at(it_joint_actuator->first)->getId();
726  single_value_vector = joint_actuator_.at(it_joint_actuator->first)->receiveJointActuatorValue(single_actuator_id);
727  for(uint32_t index=0; index < single_actuator_id.size(); index++)
728  {
729  get_actuator_id.push_back(single_actuator_id.at(index));
730  get_value_vector.push_back(single_value_vector.at(index));
731  }
732  }
733 
734  std::vector<JointValue> result_vector;
735  JointValue result;
736 
737  for(uint32_t index = 0; index < joint_component_name.size(); index++)
738  {
739  for(uint32_t index2 = 0; index2 < get_actuator_id.size(); index2++)
740  {
741  if(manipulator_.getId(joint_component_name.at(index)) == get_actuator_id.at(index2))
742  {
743  double coefficient = manipulator_.getCoefficient(joint_component_name.at(index));
744  double torque_coefficient = manipulator_.getTorqueCoefficient(joint_component_name.at(index));
745  result.position = get_value_vector.at(index2).position * coefficient;
746  result.velocity = get_value_vector.at(index2).velocity * coefficient;
747  result.acceleration = get_value_vector.at(index2).acceleration * coefficient;
748  result.effort = get_value_vector.at(index2).effort * torque_coefficient;
749  manipulator_.setJointValue(joint_component_name.at(index), result);
750  result_vector.push_back(result);
751  }
752  }
753  }
754 
755  return result_vector;
756  }
757  return {};
758 }
759 
761 {
763  {
764  std::vector<JointValue> get_value_vector;
765  std::vector<uint8_t> get_actuator_id;
766  std::vector<JointValue> single_value_vector;
767  std::vector<uint8_t> single_actuator_id;
768  for(auto it_joint_actuator = joint_actuator_.begin(); it_joint_actuator != joint_actuator_.end(); it_joint_actuator++)
769  {
770  single_actuator_id = joint_actuator_.at(it_joint_actuator->first)->getId();
771  single_value_vector = joint_actuator_.at(it_joint_actuator->first)->receiveJointActuatorValue(single_actuator_id);
772 
773  for(uint32_t index=0; index < single_actuator_id.size(); index++)
774  {
775  get_actuator_id.push_back(single_actuator_id.at(index));
776  get_value_vector.push_back(single_value_vector.at(index));
777  }
778  }
779 
780  std::map<Name, Component>::iterator it;
781  std::vector<JointValue> result_vector;
782  JointValue result;
783  for (it = manipulator_.getIteratorBegin(); it != manipulator_.getIteratorEnd(); it++)
784  {
785  for(uint32_t index2 = 0; index2 < get_actuator_id.size(); index2++)
786  {
787  if(manipulator_.checkComponentType(it->first,ACTIVE_JOINT_COMPONENT) && manipulator_.getId(it->first) == get_actuator_id.at(index2))
788  {
789  double coefficient = manipulator_.getCoefficient(it->first);
790  double torque_coefficient = manipulator_.getTorqueCoefficient(it->first);
791  result.position = get_value_vector.at(index2).position * coefficient;
792  result.velocity = get_value_vector.at(index2).velocity * coefficient;
793  result.acceleration = get_value_vector.at(index2).acceleration * coefficient;
794  result.effort = get_value_vector.at(index2).effort * torque_coefficient;
795  manipulator_.setJointValue(it->first, result);
796  result_vector.push_back(result);
797  break;
798  }
799  }
800  }
801  return result_vector;
802  }
803  return {};
804 }
806 
808 {
810  {
811  double coefficient;
812  coefficient = manipulator_.getCoefficient(tool_component_name);
813  double torque_coefficient = manipulator_.getTorqueCoefficient(tool_component_name);
814  value.position = value.position / coefficient;
815  value.velocity = value.velocity / coefficient;
816  value.acceleration = value.acceleration / coefficient;
817  value.effort = value.effort / torque_coefficient;
818 
819  return tool_actuator_.at(manipulator_.getComponentActuatorName(tool_component_name))->sendToolActuatorValue(value);
820  }
821  else
822  {
823  //set to manipulator
824  manipulator_.setJointValue(tool_component_name, value);
825  return true;
826  }
827 }
828 
829 bool RobotisManipulator::sendMultipleToolActuatorValue(std::vector<Name> tool_component_name, std::vector<JointValue> value_vector)
830 {
832  {
833  for (uint32_t index = 0; index < tool_component_name.size(); index++)
834  {
835  double coefficient = manipulator_.getCoefficient(tool_component_name.at(index));
836  value_vector.at(index).position = value_vector.at(index).position / coefficient;
837  value_vector.at(index).velocity = value_vector.at(index).velocity / coefficient;
838  value_vector.at(index).acceleration = value_vector.at(index).acceleration / coefficient;
839 
840  if(!tool_actuator_.at(manipulator_.getComponentActuatorName(tool_component_name.at(index)))->sendToolActuatorValue(value_vector.at(index)))
841  return false;
842  }
843  return true;
844  }
845  else
846  {
847  //set to manipulator
848  for(uint8_t index = 0; index < tool_component_name.size(); index++)
849  manipulator_.setJointValue(tool_component_name.at(index), value_vector.at(index));
850  return true;
851  }
852 }
853 
854 bool RobotisManipulator::sendAllToolActuatorValue(std::vector<JointValue> value_vector)
855 {
857  {
858  std::vector<Name> tool_component_name;
859  tool_component_name = manipulator_.getAllToolComponentName();
860  for (uint32_t index = 0; index < tool_component_name.size(); index++)
861  {
862  double coefficient = manipulator_.getCoefficient(tool_component_name.at(index));
863  value_vector.at(index).position = value_vector.at(index).position / coefficient;
864  value_vector.at(index).velocity = value_vector.at(index).velocity / coefficient;
865  value_vector.at(index).acceleration = value_vector.at(index).acceleration / coefficient;
866 
867  if(!tool_actuator_.at(manipulator_.getComponentActuatorName(tool_component_name.at(index)))->sendToolActuatorValue(value_vector.at(index)))
868  return false;
869  }
870  return true;
871  }
872  else
873  {
874  //set to manipualtor
875  manipulator_.setAllToolValue(value_vector);
876  }
877  return false;
878 }
879 
881 {
883  {
884  JointValue result;
886 
887  double coefficient = manipulator_.getCoefficient(tool_component_name);
888  result.position = result.position * coefficient;
889  result.velocity = result.velocity * coefficient;
890  result.acceleration = result.acceleration * coefficient;
891 
892  manipulator_.setJointValue(tool_component_name, result);
893  return result;
894  }
895  return {};
896 }
897 
898 std::vector<JointValue> RobotisManipulator::receiveMultipleToolActuatorValue(std::vector<Name> tool_component_name)
899 {
901  {
902  std::vector<JointValue> result_vector;
903  ActuatorValue result;
904  for (uint32_t index = 0; index < tool_component_name.size(); index++)
905  {
906  result = tool_actuator_.at(manipulator_.getComponentActuatorName(tool_component_name.at(index)))->receiveToolActuatorValue();
907 
908  double coefficient = manipulator_.getCoefficient(tool_component_name.at(index));
909  result.position = result.position * coefficient;
910  result.velocity = result.velocity * coefficient;
911  result.acceleration = result.acceleration * coefficient;
912 
913  manipulator_.setJointValue(tool_component_name.at(index), result);
914  result_vector.push_back(result);
915  }
916  return result_vector;
917  }
918  return {};
919 }
920 
922 {
924  {
925  std::vector<Name> tool_component_name;
926  tool_component_name = manipulator_.getAllToolComponentName();
927  std::vector<JointValue> result_vector;
928  ActuatorValue result;
929  for (uint32_t index = 0; index < tool_component_name.size(); index++)
930  {
931  result = tool_actuator_.at(manipulator_.getComponentActuatorName(tool_component_name.at(index)))->receiveToolActuatorValue();
932  double coefficient = manipulator_.getCoefficient(tool_component_name.at(index));
933  result.position = result.position * coefficient;
934  result.velocity = result.velocity * coefficient;
935  result.acceleration = result.acceleration * coefficient;
936 
937  manipulator_.setJointValue(tool_component_name.at(index), result);
938  result_vector.push_back(result);
939  }
940  return result_vector;
941  }
942  return {};
943 }
944 
945 
946 
947 /*****************************************************************************
948 ** Time Function
949 *****************************************************************************/
951 {
952  moving_state_ = true;
953  moving_fail_flag_ = false;
955 }
956 
958 {
959  return trajectory_.getMoveTime();
960 }
961 
963 {
964  return moving_state_;
965 }
966 
968 {
969  return moving_fail_flag_;
970 }
971 
973 {
974  moving_fail_flag_ = false;
975 }
976 
977 
978 /*****************************************************************************
979 ** Check Joint Limit Function
980 *****************************************************************************/
981 bool RobotisManipulator::checkJointLimit(Name component_name, double joint_position)
982 {
983  if(trajectory_.getManipulator()->checkJointLimit(component_name, joint_position))
984  return true;
985  else
986  {
987  log::error("[checkJointLimit] Goal value exceeded limit at " + STRING(component_name) + ".");
988  return false;
989  }
990 }
991 
993 {
994  if(trajectory_.getManipulator()->checkJointLimit(component_name, value.position))
995  return true;
996  else
997  {
998  log::error("[checkJointLimit] Goal value exceeded limit at " + STRING(component_name) + ".");
999  return false;
1000  }
1001 }
1002 
1003 bool RobotisManipulator::checkJointLimit(std::vector<Name> component_name, std::vector<double> position_vector)
1004 {
1005  for(uint32_t index = 0; index < component_name.size(); index++)
1006  {
1007  if(!trajectory_.getManipulator()->checkJointLimit(component_name.at(index), position_vector.at(index)))
1008  {
1009  log::error("[checkJointLimit] Goal value exceeded limit at " + STRING(component_name.at(index)) + ".");
1010  return false;
1011  }
1012  }
1013  return true;
1014 }
1015 
1016 bool RobotisManipulator::checkJointLimit(std::vector<Name> component_name, std::vector<JointValue> value_vector)
1017 {
1018  for(uint32_t index = 0; index < component_name.size(); index++)
1019  {
1020  if(!trajectory_.getManipulator()->checkJointLimit(component_name.at(index), value_vector.at(index).position))
1021  {
1022  log::error("[checkJointLimit] Goal value exceeded limit at " + STRING(component_name.at(index)) + ".");
1023  return false;
1024  }
1025  }
1026  return true;
1027 }
1028 
1029 
1030 /*****************************************************************************
1031 ** Trajectory Control Fuction
1032 *****************************************************************************/
1034 {
1035  return &trajectory_;
1036 }
1037 
1038 bool RobotisManipulator::makeJointTrajectoryFromPresentPosition(std::vector<double> delta_goal_joint_position, double move_time, std::vector<JointValue> present_joint_value)
1039 {
1040  if(present_joint_value.size() != 0)
1041  {
1042  trajectory_.setPresentJointWaypoint(present_joint_value);
1044  }
1045 
1046  JointWaypoint present_way_point = trajectory_.getPresentJointWaypoint();
1047  std::vector<double> goal_joint_position;
1048  for(size_t i = 0; i < static_cast<size_t>(trajectory_.getManipulator()->getDOF()); i ++)
1049  goal_joint_position.push_back(present_way_point.at(i).position + delta_goal_joint_position.at(i));
1050 
1051  return makeJointTrajectory(goal_joint_position, move_time);
1052 }
1053 
1054 bool RobotisManipulator::makeJointTrajectory(std::vector<double> goal_joint_position, double move_time, std::vector<JointValue> present_joint_value)
1055 {
1057  trajectory_.setMoveTime(move_time);
1058 
1059  if(present_joint_value.size() != 0)
1060  {
1061  trajectory_.setPresentJointWaypoint(present_joint_value);
1063  }
1064 
1065  JointWaypoint present_way_point = trajectory_.getPresentJointWaypoint();
1066 
1067  JointValue goal_way_point_temp;
1068  JointWaypoint goal_way_point;
1069  for (uint8_t index = 0; index < trajectory_.getManipulator()->getDOF(); index++)
1070  {
1071  goal_way_point_temp.position = goal_joint_position.at(index);
1072  goal_way_point_temp.velocity = 0.0;
1073  goal_way_point_temp.acceleration = 0.0;
1074  goal_way_point_temp.effort = 0.0;
1075 
1076  goal_way_point.push_back(goal_way_point_temp);
1077  }
1078 
1079  if(getMovingState())
1080  {
1081  moving_state_=false;
1082  while(!step_moving_state_);
1083  }
1084  if(!trajectory_.makeJointTrajectory(present_way_point, goal_way_point))
1085  return false;
1086 
1087  startMoving();
1088  return true;
1089 }
1090 
1091 bool RobotisManipulator::makeJointTrajectory(std::vector<JointValue> goal_joint_value, double move_time, std::vector<JointValue> present_joint_value)
1092 {
1094  trajectory_.setMoveTime(move_time);
1095 
1096  if(present_joint_value.size() != 0)
1097  {
1098  trajectory_.setPresentJointWaypoint(present_joint_value);
1100  }
1101 
1102  JointWaypoint present_way_point = trajectory_.getPresentJointWaypoint();
1103 
1104  if(getMovingState())
1105  {
1106  moving_state_=false;
1107  while(!step_moving_state_);
1108  }
1109  if(!trajectory_.makeJointTrajectory(present_way_point, goal_joint_value))
1110  return false;
1111  startMoving();
1112 
1113  return true;
1114 }
1115 
1116 bool RobotisManipulator::makeJointTrajectory(Name tool_name, Eigen::Vector3d goal_position, double move_time, std::vector<JointValue> present_joint_value)
1117 {
1118  if(present_joint_value.size() != 0)
1119  {
1120  trajectory_.setPresentJointWaypoint(present_joint_value);
1122  }
1123 
1124  KinematicPose goal_pose;
1125 
1126  goal_pose.position = goal_position;
1128  return makeJointTrajectory(tool_name, goal_pose, move_time);
1129 }
1130 
1131 bool RobotisManipulator::makeJointTrajectory(Name tool_name, Eigen::Matrix3d goal_orientation, double move_time, std::vector<JointValue> present_joint_value)
1132 {
1133  if(present_joint_value.size() != 0)
1134  {
1135  trajectory_.setPresentJointWaypoint(present_joint_value);
1137  }
1138 
1139  KinematicPose goal_pose;
1140 
1142  goal_pose.orientation = goal_orientation;
1143  return makeJointTrajectory(tool_name, goal_pose, move_time);
1144 }
1145 
1146 bool RobotisManipulator::makeJointTrajectory(Name tool_name, KinematicPose goal_pose, double move_time, std::vector<JointValue> present_joint_value)
1147 {
1148  if(present_joint_value.size() != 0)
1149  {
1150  trajectory_.setPresentJointWaypoint(present_joint_value);
1152  }
1153 
1155  trajectory_.setMoveTime(move_time);
1156 
1157  JointWaypoint present_way_point = trajectory_.getPresentJointWaypoint();
1158 
1159  Pose temp_goal_pose;
1160  temp_goal_pose.kinematic = goal_pose;
1161  temp_goal_pose = trajectory_.removeWaypointDynamicData(temp_goal_pose);
1162  std::vector<JointValue> goal_joint_angle;
1163  if(kinematics_->solveInverseKinematics(trajectory_.getManipulator(), tool_name, temp_goal_pose, &goal_joint_angle))
1164  {
1165  if(getMovingState())
1166  {
1167  moving_state_=false;
1168  while(!step_moving_state_) ;
1169  }
1170  if(!trajectory_.makeJointTrajectory(present_way_point, goal_joint_angle))
1171  return false;
1172  startMoving();
1173  return true;
1174  }
1175  else
1176  {
1177  log::error("[JOINT_TRAJECTORY] Fail to solve IK");
1178  return false;
1179  }
1180 }
1181 
1182 bool RobotisManipulator::makeTaskTrajectoryFromPresentPose(Name tool_name, Eigen::Vector3d position_meter, double move_time, std::vector<JointValue> present_joint_value)
1183 {
1184  if(present_joint_value.size() != 0)
1185  {
1186  trajectory_.setPresentJointWaypoint(present_joint_value);
1188  }
1189 
1190  KinematicPose goal_pose;
1191 
1192  goal_pose.position = trajectory_.getManipulator()->getComponentPositionFromWorld(tool_name) + position_meter;
1194  return makeTaskTrajectory(tool_name, goal_pose, move_time);
1195 }
1196 
1197 bool RobotisManipulator::makeTaskTrajectoryFromPresentPose(Name tool_name, Eigen::Matrix3d orientation_meter, double move_time, std::vector<JointValue> present_joint_value)
1198 {
1199  if(present_joint_value.size() != 0)
1200  {
1201  trajectory_.setPresentJointWaypoint(present_joint_value);
1203  }
1204 
1205  KinematicPose goal_pose;
1206 
1208  goal_pose.orientation = orientation_meter * trajectory_.getManipulator()->getComponentOrientationFromWorld(tool_name);
1209  return makeTaskTrajectory(tool_name, goal_pose, move_time);
1210 }
1211 
1212 bool RobotisManipulator::makeTaskTrajectoryFromPresentPose(Name tool_name, KinematicPose goal_pose_delta, double move_time, std::vector<JointValue> present_joint_value)
1213 {
1214  if(present_joint_value.size() != 0)
1215  {
1216  trajectory_.setPresentJointWaypoint(present_joint_value);
1218  }
1219 
1220  KinematicPose goal_pose;
1221 
1222  goal_pose.position = trajectory_.getManipulator()->getComponentPositionFromWorld(tool_name) + goal_pose_delta.position;
1223  goal_pose.orientation = goal_pose_delta.orientation * trajectory_.getManipulator()->getComponentOrientationFromWorld(tool_name);
1224  return makeTaskTrajectory(tool_name, goal_pose, move_time);
1225 }
1226 
1227 bool RobotisManipulator::makeTaskTrajectory(Name tool_name, Eigen::Vector3d goal_position, double move_time, std::vector<JointValue> present_joint_value)
1228 {
1229  if(present_joint_value.size() != 0)
1230  {
1231  trajectory_.setPresentJointWaypoint(present_joint_value);
1233  }
1234 
1235  KinematicPose goal_pose;
1236 
1237  goal_pose.position = goal_position;
1239  return makeTaskTrajectory(tool_name, goal_pose, move_time);
1240 }
1241 
1242 bool RobotisManipulator::makeTaskTrajectory(Name tool_name, Eigen::Matrix3d goal_orientation, double move_time, std::vector<JointValue> present_joint_value)
1243 {
1244  if(present_joint_value.size() != 0)
1245  {
1246  trajectory_.setPresentJointWaypoint(present_joint_value);
1248  }
1249 
1250  KinematicPose goal_pose;
1251 
1253  goal_pose.orientation = goal_orientation;
1254  return makeTaskTrajectory(tool_name, goal_pose, move_time);
1255 }
1256 
1257 bool RobotisManipulator::makeTaskTrajectory(Name tool_name, KinematicPose goal_pose, double move_time, std::vector<JointValue> present_joint_value)
1258 {
1261  trajectory_.setMoveTime(move_time);
1262 
1263  if(present_joint_value.size() != 0)
1264  {
1265  trajectory_.setPresentJointWaypoint(present_joint_value);
1267  }
1268 
1269  TaskWaypoint present_task_way_point = trajectory_.getPresentTaskWaypoint(tool_name);
1270 
1271  TaskWaypoint goal_task_way_point; //data conversion
1272  goal_task_way_point.kinematic = goal_pose;
1273  goal_task_way_point = trajectory_.removeWaypointDynamicData(goal_task_way_point);
1274 
1275  Pose temp_goal_pose;
1276  temp_goal_pose.kinematic = goal_pose;
1277  temp_goal_pose = trajectory_.removeWaypointDynamicData(temp_goal_pose);
1278  std::vector<JointValue> goal_joint_angle;
1279  if(kinematics_->solveInverseKinematics(trajectory_.getManipulator(), tool_name, temp_goal_pose, &goal_joint_angle))
1280  {
1281  if(getMovingState())
1282  {
1283  moving_state_=false;
1284  while(!step_moving_state_) ;
1285  }
1286 
1287  if(!trajectory_.makeTaskTrajectory(present_task_way_point, goal_task_way_point))
1288  return false;
1289  startMoving();
1290  return true;
1291  }
1292  else
1293  {
1294  log::error("[TASK_TRAJECTORY] Fail to solve IK");
1295  return false;
1296  }
1297 }
1298 
1299 void RobotisManipulator::setCustomTrajectoryOption(Name trajectory_name, const void* arg)
1300 {
1301  trajectory_.setCustomTrajectoryOption(trajectory_name, arg);
1302 }
1303 
1304 bool RobotisManipulator::makeCustomTrajectory(Name trajectory_name, Name tool_name, const void *arg, double move_time, std::vector<JointValue> present_joint_value)
1305 {
1308  trajectory_.setMoveTime(move_time);
1309 
1310  if(present_joint_value.size() != 0)
1311  {
1312  trajectory_.setPresentJointWaypoint(present_joint_value);
1314  }
1315 
1316  TaskWaypoint present_task_way_point = trajectory_.getPresentTaskWaypoint(tool_name);
1317 
1318  if(getMovingState())
1319  {
1320  moving_state_=false;
1321  while(!step_moving_state_) ;
1322  }
1323  if(!trajectory_.makeCustomTrajectory(trajectory_name, present_task_way_point, arg))
1324  return false;
1325  startMoving();
1326  return true;
1327 }
1328 
1329 bool RobotisManipulator::makeCustomTrajectory(Name trajectory_name, const void *arg, double move_time, std::vector<JointValue> present_joint_value)
1330 {
1332  trajectory_.setMoveTime(move_time);
1333 
1334  if(present_joint_value.size() != 0)
1335  {
1336  trajectory_.setPresentJointWaypoint(present_joint_value);
1338  }
1339 
1340  JointWaypoint present_joint_way_point = trajectory_.getPresentJointWaypoint();
1341 
1342  if(getMovingState())
1343  {
1344  moving_state_=false;
1345  while(!step_moving_state_) ;
1346  }
1347  if(!trajectory_.makeCustomTrajectory(trajectory_name, present_joint_value, arg))
1348  return false;
1349  startMoving();
1350  return true;
1351 }
1352 
1353 bool RobotisManipulator::sleepTrajectory(double wait_time, std::vector<JointValue> present_joint_value)
1354 {
1356  trajectory_.setMoveTime(wait_time);
1357 
1358  if(present_joint_value.size() != 0)
1359  {
1360  trajectory_.setPresentJointWaypoint(present_joint_value);
1362  }
1363 
1364  JointWaypoint present_joint_way_point = trajectory_.getPresentJointWaypoint();
1365  JointWaypoint goal_way_point_vector = trajectory_.getPresentJointWaypoint();
1366  goal_way_point_vector = trajectory_.removeWaypointDynamicData(goal_way_point_vector);
1367 
1368  if(getMovingState())
1369  {
1370  moving_state_= false;
1371  while(!step_moving_state_) ;
1372  }
1373  if(!trajectory_.makeJointTrajectory(present_joint_way_point, goal_way_point_vector))
1374  return false;
1375  startMoving();
1376  return true;
1377 }
1378 
1379 bool RobotisManipulator::makeToolTrajectory(Name tool_name, double tool_goal_position)
1380 {
1381  JointValue tool_value;
1382  tool_value.position = tool_goal_position;
1383  tool_value.velocity = 0.0;
1384  tool_value.acceleration = 0.0;
1385  tool_value.effort =0.0;
1386 
1387  if(checkJointLimit(tool_name, tool_value))
1388  {
1389  return trajectory_.setToolGoalValue(tool_name, tool_value);
1390  }
1391  else
1392  return false;
1393 }
1394 
1395 JointWaypoint RobotisManipulator::getTrajectoryJointValue(double tick_time, int option) //Private
1396 {
1397  JointWaypoint joint_way_point_value;
1398 
1401  {
1402  joint_way_point_value = trajectory_.getJointTrajectory().getJointWaypoint(tick_time);
1403 
1405  {
1407  moving_fail_flag_ = true;
1408  moving_state_ = false;
1409  }
1410  //set present joint task value to trajectory manipulator
1411  trajectory_.setPresentJointWaypoint(joint_way_point_value);
1414  }
1415  }
1420  {
1421  TaskWaypoint task_way_point;
1422  task_way_point = trajectory_.getTaskTrajectory().getTaskWaypoint(tick_time);
1423 
1424  if(kinematics_->solveInverseKinematics(trajectory_.getManipulator(), trajectory_.getPresentControlToolName(), task_way_point, &joint_way_point_value))
1425  {
1427  {
1430  moving_fail_flag_ = true;
1431  moving_state_ = false;
1432  }
1433  }
1434  else
1435  {
1438  log::error("[TASK_TRAJECTORY] fail to solve IK");
1439  moving_fail_flag_ = true;
1440  moving_state_ = false;
1441  }
1442  //set present joint task value to trajectory manipulator
1443  trajectory_.setPresentJointWaypoint(joint_way_point_value);
1445  }
1450  {
1451  joint_way_point_value = trajectory_.getCustomJointTrajectory(trajectory_.getPresentCustomTrajectoryName())->getJointWaypoint(tick_time);
1452 
1454  {
1456  moving_fail_flag_ = true;
1457  moving_state_ = false;
1458  }
1459  //set present joint task value to trajectory manipulator
1460  trajectory_.setPresentJointWaypoint(joint_way_point_value);
1463  }
1464  }
1466  {
1467  TaskWaypoint task_way_point;
1468  task_way_point = trajectory_.getCustomTaskTrajectory(trajectory_.getPresentCustomTrajectoryName())->getTaskWaypoint(tick_time);
1469 
1470  if(kinematics_->solveInverseKinematics(trajectory_.getManipulator(), trajectory_.getPresentControlToolName(), task_way_point, &joint_way_point_value))
1471  {
1473  {
1476  moving_fail_flag_ = true;
1477  moving_state_ = false;
1478  }
1479  }
1480  else
1481  {
1484  log::error("[CUSTOM_TASK_TRAJECTORY] fail to solve IK");
1485  moving_fail_flag_ = true;
1486  moving_state_ = false;
1487  }
1488  //set present joint task value to trajectory manipulator
1489  trajectory_.setPresentJointWaypoint(joint_way_point_value);
1491  }
1493 
1495  {
1496  std::map<Name, double> joint_torque_map;
1497  if(option == DYNAMICS_ALL_SOVING)
1498  {
1499  if(dynamics_->solveInverseDynamics(*trajectory_.getManipulator(), &joint_torque_map))
1500  {
1502  std::vector<double> joint_torque;
1503  for(uint8_t i = 0; i < names.size(); i++)
1504  {
1505  if(joint_torque_map.find(names.at(i))!=joint_torque_map.end())
1506  joint_torque.push_back(joint_torque_map.at(names.at(i)));
1507  else
1508  joint_torque.push_back(0.0);
1509  }
1510  robotis_manipulator::setEffortToValue(&joint_way_point_value, joint_torque);
1511  }
1512  else
1513  {
1514  log::error("[getTrajectoryJointValue] fail to add goal effort.");
1515  }
1516  }
1517  else if(option == DYNAMICS_GRAVITY_ONLY)
1518  {
1522  }
1523 
1524  if(dynamics_->solveInverseDynamics(*trajectory_.getManipulator(), &joint_torque_map))
1525  {
1527  std::vector<double> joint_torque;
1528  for(uint8_t i = 0; i < names.size(); i++)
1529  {
1530  if(joint_torque_map.find(names.at(i))!=joint_torque_map.end())
1531  joint_torque.push_back(joint_torque_map.at(names.at(i)));
1532  else
1533  joint_torque.push_back(0.0);
1534  }
1535  // add effort data
1536  robotis_manipulator::setEffortToValue(&joint_way_point_value, joint_torque);
1537  }
1538  }
1539  else
1540  {
1541  // not solve
1542  }
1543  //set present joint task value to trajectory manipulator
1544  trajectory_.setPresentJointWaypoint(joint_way_point_value);
1547  }
1548  }
1549 
1550  return joint_way_point_value;
1551 }
1552 
1553 std::vector<JointValue> RobotisManipulator::getJointGoalValueFromTrajectory(double present_time, int option)
1554 {
1555  trajectory_.setPresentTime(present_time);
1556 
1558  {
1561  else
1564  }
1565 
1566  if(moving_state_)
1567  {
1568  step_moving_state_ = false;
1569  JointWaypoint joint_goal_way_point;
1570  double tick_time = trajectory_.getTickTime();
1571 
1572  if(tick_time < trajectory_.getMoveTime())
1573  {
1574  moving_state_ = true;
1575  joint_goal_way_point = getTrajectoryJointValue(tick_time, option);
1576  }
1577  else
1578  {
1579  moving_state_ = false;
1580  joint_goal_way_point = getTrajectoryJointValue(trajectory_.getMoveTime(), option);
1581  }
1582  step_moving_state_ = true;
1583  return joint_goal_way_point;
1584  }
1585  return {};
1586 }
1587 
1588 std::vector<JointValue> RobotisManipulator::getJointGoalValueFromTrajectoryTickTime(double tick_time)
1589 {
1591  {
1594  else
1597  }
1598 
1599  if(moving_state_)
1600  {
1601  step_moving_state_ = false;
1602  JointWaypoint joint_goal_way_point ;
1603  if(tick_time < trajectory_.getMoveTime())
1604  {
1605  moving_state_ = true;
1606  joint_goal_way_point = getTrajectoryJointValue(tick_time);
1607  }
1608  else
1609  {
1610  moving_state_ = false;
1611  joint_goal_way_point = getTrajectoryJointValue(trajectory_.getMoveTime());
1612  }
1613  step_moving_state_ = true;
1614  return joint_goal_way_point;
1615  }
1616  return {};
1617 }
1618 
1620 {
1621  moving_state_ = false;
1623  {
1625  trajectory_.setPresentJointWaypoint(joint_way_point_value);
1628  }
1629 }
1630 
1631 std::vector<JointValue> RobotisManipulator::getToolGoalValue()
1632 {
1633  std::vector<JointValue> result_vector;
1634  std::vector<Name> tool_component_name = trajectory_.getManipulator()->getAllToolComponentName();
1635  for(uint32_t index =0; index<tool_component_name.size(); index++)
1636  {
1637  result_vector.push_back(trajectory_.getToolGoalValue(tool_component_name.at(index)));
1638  }
1639  return result_vector;
1640 }
bool checkJointLimit(Name component_name, double position)
void setComponentActuatorName(Name component_name, Name actuator_name)
bool makeJointTrajectory(JointWaypoint start_way_point, JointWaypoint goal_way_point)
makeJointTrajectory
JointActuator * getJointActuator(Name actuator_name)
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 object_mass=0.0, Eigen::Matrix3d object_inertia_tensor=Eigen::Matrix3d::Identity(), Eigen::Vector3d object_center_of_mass=Eigen::Vector3d::Zero())
std::vector< JointValue > getToolGoalValue()
getToolGoalValue
bool sleepTrajectory(double wait_time, std::vector< JointValue > present_joint_value={})
sleepTrajectory
std::vector< JointValue > receiveAllToolActuatorValue()
std::vector< JointValue > getJointGoalValueFromTrajectoryTickTime(double tick_time)
void setPresentJointWaypoint(JointWaypoint joint_value_vector)
std::vector< JointValue > getAllJointValue()
bool setToolGoalValue(Name tool_name, JointValue tool_goal_value)
setToolGoalValue
std::map< Name, Component >::iterator getIteratorEnd()
std::vector< JointValue > getJointGoalValueFromTrajectory(double present_time, int option=DYNAMICS_ALL_SOVING)
getJointGoalValueFromTrajectory
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)
virtual void solveForwardKinematics(Manipulator *manipulator)=0
bool makeTaskTrajectoryFromPresentPose(Name tool_name, Eigen::Vector3d position_meter, double move_time, std::vector< JointValue > present_joint_value={})
makeTaskTrajectoryFromPresentPose
void setPresentControlToolName(Name present_control_tool_name)
virtual bool solveInverseKinematics(Manipulator *manipulator, Name tool_name, Pose target_pose, std::vector< JointValue > *goal_joint_position)=0
void addCustomTrajectory(Name trajectory_name, CustomJointTrajectory *custom_trajectory)
void initTrajectoryWaypoint(Manipulator actual_manipulator, Kinematics *kinematics=nullptr)
Eigen::Matrix3d getComponentOrientationFromWorld(Name component_name)
void setTorqueCoefficient(Name component_name, double torque_coefficient)
bool checkComponentType(Name component_name, ComponentType component_type)
bool checkTrajectoryType(TrajectoryType trajectory_type)
std::vector< JointValue > getAllActiveJointValue()
bool makeTaskTrajectory(Name tool_name, Eigen::Vector3d goal_position, double move_time, std::vector< JointValue > present_joint_value={})
makeTaskTrajectory
JointWaypoint getTrajectoryJointValue(double tick_time, int option=0)
bool makeCustomTrajectory(Name trajectory_name, Name tool_name, const void *arg, double move_time, std::vector< JointValue > present_joint_value={})
makeCustomTrajectory
virtual Eigen::MatrixXd jacobian(Manipulator *manipulator, Name tool_name)=0
bool setEffortToValue(std::vector< JointValue > *value, std::vector< double > effort)
DynamicPose getDynamicPose(Name component_name)
bool makeJointTrajectory(std::vector< double > goal_joint_position, double move_time, std::vector< JointValue > present_joint_value={})
makeJointTrajectory
bool solveGravityTerm(std::map< Name, double > *joint_torque)
KinematicPose getKinematicPose(Name component_name)
void setPresentTaskWaypoint(Name tool_name, TaskWaypoint tool_position_value_vector)
bool sendJointActuatorValue(Name joint_component_name, JointValue value)
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)
bool checkJointLimit(Name Component_name, double value)
virtual bool setOption(STRING param_name, const void *arg)=0
void setTrajectoryType(TrajectoryType trajectory_type)
CustomJointTrajectory * getCustomJointTrajectory(Name name)
std::vector< JointValue > JointWaypoint
std::vector< JointValue > getAllJointValue()
bool makeCustomTrajectory(Name trajectory_name, JointWaypoint start_way_point, const void *arg)
makeCustomTrajectory
std::vector< JointValue > receiveMultipleJointActuatorValue(std::vector< Name > joint_component_name)
Name getComponentActuatorName(Name component_name)
void setAllActiveJointValue(std::vector< JointValue > joint_value_vector)
uint8_t getToolActuatorId(Name actuator_name)
void addComponentChild(Name my_name, Name child_name)
bool makeJointTrajectoryFromPresentPosition(std::vector< double > delta_goal_joint_position, double move_time, std::vector< JointValue > present_joint_value={})
makeJointTrajectoryFromPresentPosition
std::vector< JointValue > receiveAllJointActuatorValue()
void setToolActuatorMode(Name actuator_name, const void *arg)
std::vector< JointValue > getAllActiveJointValue()
virtual bool solveForwardDynamics(Manipulator *manipulator, std::map< Name, double > joint_torque)=0
void setDynamicsEnvironments(STRING param_name, const void *arg)
bool makeToolTrajectory(Name tool_name, double tool_goal_position)
makeToolTrajectory
ToolActuator * getToolActuator(Name actuator_name)
DynamicPose getComponentDynamicPoseFromWorld(Name component_name)
virtual void setOption(const void *arg)=0
double getTorqueCoefficient(Name component_name)
#define DYNAMICS_ALL_SOVING
bool solveInverseDynamics(std::map< Name, double > *joint_torque)
void setTorqueCoefficient(Name component_name, double torque_coefficient)
std::vector< uint8_t > getJointActuatorId(Name actuator_name)
JointValue receiveJointActuatorValue(Name joint_component_name)
virtual bool solveInverseDynamics(Manipulator manipulator, std::map< Name, double > *joint_torque)=0
bool sendAllToolActuatorValue(std::vector< JointValue > value_vector)
bool makeTaskTrajectory(TaskWaypoint start_way_point, TaskWaypoint goal_way_point)
makeTaskTrajectory
bool sendMultipleJointActuatorValue(std::vector< Name > joint_component_name, std::vector< JointValue > value_vector)
bool sendAllJointActuatorValue(std::vector< JointValue > value_vector)
std::vector< JointValue > receiveMultipleToolActuatorValue(std::vector< Name > tool_component_name)
Eigen::MatrixXd jacobian(Name tool_name)
virtual bool setEnvironments(STRING param_name, const void *arg)=0
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 setCustomTrajectoryOption(Name trajectory_name, const void *arg)
setCustomTrajectoryOption
std::map< Name, ToolActuator * > tool_actuator_
bool solveInverseKinematics(Name tool_name, Pose goal_pose, std::vector< JointValue > *goal_joint_value)
bool sendMultipleToolActuatorValue(std::vector< Name > tool_component_name, std::vector< JointValue > value_vector)
Eigen::Vector3d getComponentPositionFromWorld(Name component_name)
void addComponentChild(Name my_name, Name child_name)
JointWaypoint removeWaypointDynamicData(JointWaypoint value)
void solveForwardDynamics(std::map< Name, double > joint_torque)
KinematicPose getComponentKinematicPoseFromWorld(Name component_name)
void setAllToolValue(std::vector< JointValue > tool_value_vector)
std::map< Name, Component >::iterator getIteratorBegin()
void addCustomTrajectory(Name trajectory_name, CustomJointTrajectory *custom_trajectory)
bool sendToolActuatorValue(Name tool_component_name, JointValue value)
#define DYNAMICS_GRAVITY_ONLY
void addKinematics(Kinematics *kinematics)
JointValue receiveToolActuatorValue(Name tool_component_name)
void setDynamicsOption(STRING param_name, const void *arg)
std::map< Name, JointActuator * > joint_actuator_
void addJointActuator(Name actuator_name, JointActuator *joint_actuator, std::vector< uint8_t > id_array, const void *arg)
void setJointActuatorMode(Name actuator_name, std::vector< uint8_t > id_array, const void *arg)
void setCustomTrajectoryOption(Name trajectory_name, const void *arg)
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 addWorld(Name world_name, Name child_name, Eigen::Vector3d world_position=Eigen::Vector3d::Zero(), Eigen::Matrix3d world_orientation=Eigen::Matrix3d::Identity())
void addToolActuator(Name tool_name, ToolActuator *tool_actuator, uint8_t id, const void *arg)


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