moveit2
The MoveIt Motion Planning Framework for ROS 2.
robot_state.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * Copyright (c) 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Ioan Sucan */
37 
38 #pragma once
39 
43 #include <sensor_msgs/msg/joint_state.hpp>
44 #include <visualization_msgs/msg/marker_array.hpp>
45 #include <std_msgs/msg/color_rgba.hpp>
46 #include <geometry_msgs/msg/twist.hpp>
47 #include <cassert>
48 
49 #include <rclcpp/duration.hpp>
50 
51 /* Terminology
52  * Model Frame: RobotModel's root frame == PlanningScene's planning frame
53  If the SRDF defines a virtual, non-fixed (e.g. floating) joint, this is the parent of this virtual joint.
54  Otherwise, it is the root link of the URDF model.
55  * Dirty Link Transforms: a caching tool for reducing the frequency of calculating forward kinematics
56 */
57 
58 namespace moveit
59 {
60 namespace core
61 {
62 MOVEIT_CLASS_FORWARD(RobotState); // Defines RobotStatePtr, ConstPtr, WeakPtr... etc
63 
68 typedef std::function<bool(RobotState* robot_state, const JointModelGroup* joint_group,
69  const double* joint_group_variable_values)>
71 
90 {
91 public:
94  RobotState(const RobotModelConstPtr& robot_model);
95  ~RobotState();
96 
98  RobotState(const RobotState& other);
99 
101  RobotState& operator=(const RobotState& other);
102 
104  const RobotModelConstPtr& getRobotModel() const
105  {
106  return robot_model_;
107  }
108 
110  std::size_t getVariableCount() const
111  {
112  return robot_model_->getVariableCount();
113  }
114 
116  const std::vector<std::string>& getVariableNames() const
117  {
118  return robot_model_->getVariableNames();
119  }
120 
122  const LinkModel* getLinkModel(const std::string& link) const
123  {
124  return robot_model_->getLinkModel(link);
125  }
126 
128  const JointModel* getJointModel(const std::string& joint) const
129  {
130  return robot_model_->getJointModel(joint);
131  }
132 
134  const JointModelGroup* getJointModelGroup(const std::string& group) const
135  {
136  return robot_model_->getJointModelGroup(group);
137  }
138 
148  {
149  return position_;
150  }
151 
154  const double* getVariablePositions() const
155  {
156  return position_;
157  }
158 
162  void setVariablePositions(const double* position);
163 
167  void setVariablePositions(const std::vector<double>& position)
168  {
169  assert(robot_model_->getVariableCount() <= position.size()); // checked only in debug mode
170  setVariablePositions(&position[0]);
171  }
172 
175  void setVariablePositions(const std::map<std::string, double>& variable_map);
176 
179  void setVariablePositions(const std::map<std::string, double>& variable_map,
180  std::vector<std::string>& missing_variables);
181 
184  void setVariablePositions(const std::vector<std::string>& variable_names,
185  const std::vector<double>& variable_position);
186 
188  void setVariablePosition(const std::string& variable, double value)
189  {
190  setVariablePosition(robot_model_->getVariableIndex(variable), value);
191  }
192 
195  void setVariablePosition(int index, double value)
196  {
197  position_[index] = value;
198  const JointModel* jm = robot_model_->getJointOfVariable(index);
199  if (jm)
200  {
201  markDirtyJointTransforms(jm);
202  updateMimicJoint(jm);
203  }
204  }
205 
207  double getVariablePosition(const std::string& variable) const
208  {
209  return position_[robot_model_->getVariableIndex(variable)];
210  }
211 
215  double getVariablePosition(int index) const
216  {
217  return position_[index];
218  }
219 
229  bool hasVelocities() const
230  {
231  return has_velocity_;
232  }
233 
237  {
238  markVelocity();
239  return velocity_;
240  }
241 
244  const double* getVariableVelocities() const
245  {
246  return velocity_;
247  }
248 
250  void zeroVelocities();
251 
253  void setVariableVelocities(const double* velocity)
254  {
255  has_velocity_ = true;
256  // assume everything is in order in terms of array lengths (for efficiency reasons)
257  memcpy(velocity_, velocity, robot_model_->getVariableCount() * sizeof(double));
258  }
259 
261  void setVariableVelocities(const std::vector<double>& velocity)
262  {
263  assert(robot_model_->getVariableCount() <= velocity.size()); // checked only in debug mode
264  setVariableVelocities(&velocity[0]);
265  }
266 
269  void setVariableVelocities(const std::map<std::string, double>& variable_map);
270 
273  void setVariableVelocities(const std::map<std::string, double>& variable_map,
274  std::vector<std::string>& missing_variables);
275 
278  void setVariableVelocities(const std::vector<std::string>& variable_names,
279  const std::vector<double>& variable_velocity);
280 
282  void setVariableVelocity(const std::string& variable, double value)
283  {
284  setVariableVelocity(robot_model_->getVariableIndex(variable), value);
285  }
286 
289  void setVariableVelocity(int index, double value)
290  {
291  markVelocity();
292  velocity_[index] = value;
293  }
294 
296  double getVariableVelocity(const std::string& variable) const
297  {
298  return velocity_[robot_model_->getVariableIndex(variable)];
299  }
300 
304  double getVariableVelocity(int index) const
305  {
306  return velocity_[index];
307  }
308 
310  void dropVelocities();
311 
322  bool hasAccelerations() const
323  {
324  return has_acceleration_;
325  }
326 
331  {
332  markAcceleration();
333  return acceleration_;
334  }
335 
338  const double* getVariableAccelerations() const
339  {
340  return acceleration_;
341  }
342 
344  void zeroAccelerations();
345 
348  void setVariableAccelerations(const double* acceleration)
349  {
350  has_acceleration_ = true;
351  has_effort_ = false;
352 
353  // assume everything is in order in terms of array lengths (for efficiency reasons)
354  memcpy(acceleration_, acceleration, robot_model_->getVariableCount() * sizeof(double));
355  }
356 
359  void setVariableAccelerations(const std::vector<double>& acceleration)
360  {
361  assert(robot_model_->getVariableCount() <= acceleration.size()); // checked only in debug mode
362  setVariableAccelerations(&acceleration[0]);
363  }
364 
367  void setVariableAccelerations(const std::map<std::string, double>& variable_map);
368 
372  void setVariableAccelerations(const std::map<std::string, double>& variable_map,
373  std::vector<std::string>& missing_variables);
374 
377  void setVariableAccelerations(const std::vector<std::string>& variable_names,
378  const std::vector<double>& variable_acceleration);
379 
381  void setVariableAcceleration(const std::string& variable, double value)
382  {
383  setVariableAcceleration(robot_model_->getVariableIndex(variable), value);
384  }
385 
388  void setVariableAcceleration(int index, double value)
389  {
390  markAcceleration();
391  acceleration_[index] = value;
392  }
393 
395  double getVariableAcceleration(const std::string& variable) const
396  {
397  return acceleration_[robot_model_->getVariableIndex(variable)];
398  }
399 
403  double getVariableAcceleration(int index) const
404  {
405  return acceleration_[index];
406  }
407 
409  void dropAccelerations();
410 
420  bool hasEffort() const
421  {
422  return has_effort_;
423  }
424 
429  {
430  markEffort();
431  return effort_;
432  }
433 
436  const double* getVariableEffort() const
437  {
438  return effort_;
439  }
440 
442  void zeroEffort();
443 
445  void setVariableEffort(const double* effort)
446  {
447  has_effort_ = true;
448  has_acceleration_ = false;
449  // assume everything is in order in terms of array lengths (for efficiency reasons)
450  memcpy(effort_, effort, robot_model_->getVariableCount() * sizeof(double));
451  }
452 
454  void setVariableEffort(const std::vector<double>& effort)
455  {
456  assert(robot_model_->getVariableCount() <= effort.size()); // checked only in debug mode
457  setVariableEffort(&effort[0]);
458  }
459 
461  void setVariableEffort(const std::map<std::string, double>& variable_map);
462 
465  void setVariableEffort(const std::map<std::string, double>& variable_map, std::vector<std::string>& missing_variables);
466 
468  void setVariableEffort(const std::vector<std::string>& variable_names,
469  const std::vector<double>& variable_acceleration);
470 
472  void setVariableEffort(const std::string& variable, double value)
473  {
474  setVariableEffort(robot_model_->getVariableIndex(variable), value);
475  }
476 
479  void setVariableEffort(int index, double value)
480  {
481  markEffort();
482  effort_[index] = value;
483  }
484 
486  double getVariableEffort(const std::string& variable) const
487  {
488  return effort_[robot_model_->getVariableIndex(variable)];
489  }
490 
494  double getVariableEffort(int index) const
495  {
496  return effort_[index];
497  }
498 
500  void dropEffort();
501 
503  void dropDynamics();
504 
506  void invertVelocity();
507 
515  void setJointPositions(const std::string& joint_name, const double* position)
516  {
517  setJointPositions(robot_model_->getJointModel(joint_name), position);
518  }
519 
520  void setJointPositions(const std::string& joint_name, const std::vector<double>& position)
521  {
522  setJointPositions(robot_model_->getJointModel(joint_name), &position[0]);
523  }
524 
525  void setJointPositions(const JointModel* joint, const std::vector<double>& position)
526  {
527  setJointPositions(joint, &position[0]);
528  }
529 
530  void setJointPositions(const JointModel* joint, const double* position)
531  {
532  memcpy(position_ + joint->getFirstVariableIndex(), position, joint->getVariableCount() * sizeof(double));
533  markDirtyJointTransforms(joint);
534  updateMimicJoint(joint);
535  }
536 
537  void setJointPositions(const std::string& joint_name, const Eigen::Isometry3d& transform)
538  {
539  setJointPositions(robot_model_->getJointModel(joint_name), transform);
540  }
541 
542  void setJointPositions(const JointModel* joint, const Eigen::Isometry3d& transform)
543  {
544  joint->computeVariablePositions(transform, position_ + joint->getFirstVariableIndex());
545  markDirtyJointTransforms(joint);
546  updateMimicJoint(joint);
547  }
548 
549  void setJointVelocities(const JointModel* joint, const double* velocity)
550  {
551  has_velocity_ = true;
552  memcpy(velocity_ + joint->getFirstVariableIndex(), velocity, joint->getVariableCount() * sizeof(double));
553  }
554 
555  void setJointEfforts(const JointModel* joint, const double* effort);
556 
557  const double* getJointPositions(const std::string& joint_name) const
558  {
559  return getJointPositions(robot_model_->getJointModel(joint_name));
560  }
561 
562  const double* getJointPositions(const JointModel* joint) const
563  {
564  return position_ + joint->getFirstVariableIndex();
565  }
566 
567  const double* getJointVelocities(const std::string& joint_name) const
568  {
569  return getJointVelocities(robot_model_->getJointModel(joint_name));
570  }
571 
572  const double* getJointVelocities(const JointModel* joint) const
573  {
574  return velocity_ + joint->getFirstVariableIndex();
575  }
576 
577  const double* getJointAccelerations(const std::string& joint_name) const
578  {
579  return getJointAccelerations(robot_model_->getJointModel(joint_name));
580  }
581 
582  const double* getJointAccelerations(const JointModel* joint) const
583  {
584  return acceleration_ + joint->getFirstVariableIndex();
585  }
586 
587  const double* getJointEffort(const std::string& joint_name) const
588  {
589  return getJointEffort(robot_model_->getJointModel(joint_name));
590  }
591 
592  const double* getJointEffort(const JointModel* joint) const
593  {
594  return effort_ + joint->getFirstVariableIndex();
595  }
596 
605  void setJointGroupPositions(const std::string& joint_group_name, const double* gstate)
606  {
607  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
608  if (jmg)
609  setJointGroupPositions(jmg, gstate);
610  }
611 
614  void setJointGroupPositions(const std::string& joint_group_name, const std::vector<double>& gstate)
615  {
616  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
617  if (jmg)
618  {
619  assert(gstate.size() == jmg->getVariableCount());
620  setJointGroupPositions(jmg, &gstate[0]);
621  }
622  }
623 
626  void setJointGroupPositions(const JointModelGroup* group, const std::vector<double>& gstate)
627  {
628  assert(gstate.size() == group->getVariableCount());
629  setJointGroupPositions(group, &gstate[0]);
630  }
631 
634  void setJointGroupPositions(const JointModelGroup* group, const double* gstate);
635 
638  void setJointGroupPositions(const std::string& joint_group_name, const Eigen::VectorXd& values)
639  {
640  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
641  if (jmg)
642  {
643  assert(values.size() == jmg->getVariableCount());
644  setJointGroupPositions(jmg, values);
645  }
646  }
647 
650  void setJointGroupPositions(const JointModelGroup* group, const Eigen::VectorXd& values);
651 
655  void setJointGroupActivePositions(const JointModelGroup* group, const std::vector<double>& gstate);
656 
660  void setJointGroupActivePositions(const std::string& joint_group_name, const std::vector<double>& gstate)
661  {
662  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
663  if (jmg)
664  {
665  assert(gstate.size() == jmg->getActiveVariableCount());
666  setJointGroupActivePositions(jmg, gstate);
667  }
668  }
669 
673  void setJointGroupActivePositions(const JointModelGroup* group, const Eigen::VectorXd& values);
674 
678  void setJointGroupActivePositions(const std::string& joint_group_name, const Eigen::VectorXd& values)
679  {
680  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
681  if (jmg)
682  {
683  assert(values.size() == jmg->getActiveVariableCount());
684  setJointGroupActivePositions(jmg, values);
685  }
686  }
687 
691  void copyJointGroupPositions(const std::string& joint_group_name, std::vector<double>& gstate) const
692  {
693  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
694  if (jmg)
695  {
696  gstate.resize(jmg->getVariableCount());
697  copyJointGroupPositions(jmg, &gstate[0]);
698  }
699  }
700 
704  void copyJointGroupPositions(const std::string& joint_group_name, double* gstate) const
705  {
706  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
707  if (jmg)
708  copyJointGroupPositions(jmg, gstate);
709  }
710 
714  void copyJointGroupPositions(const JointModelGroup* group, std::vector<double>& gstate) const
715  {
716  gstate.resize(group->getVariableCount());
717  copyJointGroupPositions(group, &gstate[0]);
718  }
719 
723  void copyJointGroupPositions(const JointModelGroup* group, double* gstate) const;
724 
728  void copyJointGroupPositions(const std::string& joint_group_name, Eigen::VectorXd& values) const
729  {
730  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
731  if (jmg)
732  copyJointGroupPositions(jmg, values);
733  }
734 
738  void copyJointGroupPositions(const JointModelGroup* group, Eigen::VectorXd& values) const;
739 
748  void setJointGroupVelocities(const std::string& joint_group_name, const double* gstate)
749  {
750  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
751  if (jmg)
752  setJointGroupVelocities(jmg, gstate);
753  }
754 
757  void setJointGroupVelocities(const std::string& joint_group_name, const std::vector<double>& gstate)
758  {
759  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
760  if (jmg)
761  setJointGroupVelocities(jmg, &gstate[0]);
762  }
763 
766  void setJointGroupVelocities(const JointModelGroup* group, const std::vector<double>& gstate)
767  {
768  setJointGroupVelocities(group, &gstate[0]);
769  }
770 
773  void setJointGroupVelocities(const JointModelGroup* group, const double* gstate);
774 
777  void setJointGroupVelocities(const std::string& joint_group_name, const Eigen::VectorXd& values)
778  {
779  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
780  if (jmg)
781  setJointGroupVelocities(jmg, values);
782  }
783 
786  void setJointGroupVelocities(const JointModelGroup* group, const Eigen::VectorXd& values);
787 
791  void copyJointGroupVelocities(const std::string& joint_group_name, std::vector<double>& gstate) const
792  {
793  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
794  if (jmg)
795  {
796  gstate.resize(jmg->getVariableCount());
797  copyJointGroupVelocities(jmg, &gstate[0]);
798  }
799  }
800 
804  void copyJointGroupVelocities(const std::string& joint_group_name, double* gstate) const
805  {
806  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
807  if (jmg)
808  copyJointGroupVelocities(jmg, gstate);
809  }
810 
814  void copyJointGroupVelocities(const JointModelGroup* group, std::vector<double>& gstate) const
815  {
816  gstate.resize(group->getVariableCount());
817  copyJointGroupVelocities(group, &gstate[0]);
818  }
819 
823  void copyJointGroupVelocities(const JointModelGroup* group, double* gstate) const;
824 
828  void copyJointGroupVelocities(const std::string& joint_group_name, Eigen::VectorXd& values) const
829  {
830  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
831  if (jmg)
832  copyJointGroupVelocities(jmg, values);
833  }
834 
838  void copyJointGroupVelocities(const JointModelGroup* group, Eigen::VectorXd& values) const;
839 
848  void setJointGroupAccelerations(const std::string& joint_group_name, const double* gstate)
849  {
850  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
851  if (jmg)
852  setJointGroupAccelerations(jmg, gstate);
853  }
854 
857  void setJointGroupAccelerations(const std::string& joint_group_name, const std::vector<double>& gstate)
858  {
859  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
860  if (jmg)
861  setJointGroupAccelerations(jmg, &gstate[0]);
862  }
863 
866  void setJointGroupAccelerations(const JointModelGroup* group, const std::vector<double>& gstate)
867  {
868  setJointGroupAccelerations(group, &gstate[0]);
869  }
870 
873  void setJointGroupAccelerations(const JointModelGroup* group, const double* gstate);
874 
877  void setJointGroupAccelerations(const std::string& joint_group_name, const Eigen::VectorXd& values)
878  {
879  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
880  if (jmg)
881  setJointGroupAccelerations(jmg, values);
882  }
883 
886  void setJointGroupAccelerations(const JointModelGroup* group, const Eigen::VectorXd& values);
887 
891  void copyJointGroupAccelerations(const std::string& joint_group_name, std::vector<double>& gstate) const
892  {
893  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
894  if (jmg)
895  {
896  gstate.resize(jmg->getVariableCount());
897  copyJointGroupAccelerations(jmg, &gstate[0]);
898  }
899  }
900 
904  void copyJointGroupAccelerations(const std::string& joint_group_name, double* gstate) const
905  {
906  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
907  if (jmg)
908  copyJointGroupAccelerations(jmg, gstate);
909  }
910 
914  void copyJointGroupAccelerations(const JointModelGroup* group, std::vector<double>& gstate) const
915  {
916  gstate.resize(group->getVariableCount());
917  copyJointGroupAccelerations(group, &gstate[0]);
918  }
919 
923  void copyJointGroupAccelerations(const JointModelGroup* group, double* gstate) const;
924 
928  void copyJointGroupAccelerations(const std::string& joint_group_name, Eigen::VectorXd& values) const
929  {
930  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
931  if (jmg)
932  copyJointGroupAccelerations(jmg, values);
933  }
934 
938  void copyJointGroupAccelerations(const JointModelGroup* group, Eigen::VectorXd& values) const;
939 
952  bool setFromIK(const JointModelGroup* group, const geometry_msgs::msg::Pose& pose, double timeout = 0.0,
956 
964  bool setFromIK(const JointModelGroup* group, const geometry_msgs::msg::Pose& pose, const std::string& tip,
965  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
968 
975  bool setFromIK(const JointModelGroup* group, const Eigen::Isometry3d& pose, double timeout = 0.0,
979 
986  bool setFromIK(const JointModelGroup* group, const Eigen::Isometry3d& pose, const std::string& tip,
987  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
990 
999  bool setFromIK(const JointModelGroup* group, const Eigen::Isometry3d& pose, const std::string& tip,
1000  const std::vector<double>& consistency_limits, double timeout = 0.0,
1004 
1014  bool setFromIK(const JointModelGroup* group, const EigenSTL::vector_Isometry3d& poses,
1015  const std::vector<std::string>& tips, double timeout = 0.0,
1019 
1030  bool setFromIK(const JointModelGroup* group, const EigenSTL::vector_Isometry3d& poses,
1031  const std::vector<std::string>& tips, const std::vector<std::vector<double>>& consistency_limits,
1032  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
1035 
1044  bool setFromIKSubgroups(const JointModelGroup* group, const EigenSTL::vector_Isometry3d& poses,
1045  const std::vector<std::string>& tips,
1046  const std::vector<std::vector<double>>& consistency_limits, double timeout = 0.0,
1049 
1057  bool setFromDiffIK(const JointModelGroup* group, const Eigen::VectorXd& twist, const std::string& tip, double dt,
1059 
1067  bool setFromDiffIK(const JointModelGroup* group, const geometry_msgs::msg::Twist& twist, const std::string& tip,
1068  double dt, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn());
1069 
1103  [[deprecated]] double
1104  computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1105  const Eigen::Vector3d& direction, bool global_reference_frame, double distance, double max_step,
1106  double jump_threshold_factor,
1109 
1119  [[deprecated]] double
1120  computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1121  const Eigen::Isometry3d& target, bool global_reference_frame, double max_step,
1122  double jump_threshold_factor,
1125 
1135  [[deprecated]] double
1136  computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1137  const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame, double max_step,
1138  double jump_threshold_factor,
1141 
1151  bool getJacobian(const JointModelGroup* group, const LinkModel* link, const Eigen::Vector3d& reference_point_position,
1152  Eigen::MatrixXd& jacobian, bool use_quaternion_representation = false) const;
1153 
1163  bool getJacobian(const JointModelGroup* group, const LinkModel* link, const Eigen::Vector3d& reference_point_position,
1164  Eigen::MatrixXd& jacobian, bool use_quaternion_representation = false)
1165  {
1167  return static_cast<const RobotState*>(this)->getJacobian(group, link, reference_point_position, jacobian,
1168  use_quaternion_representation);
1169  }
1170 
1177  Eigen::MatrixXd getJacobian(const JointModelGroup* group,
1178  const Eigen::Vector3d& reference_point_position = Eigen::Vector3d(0.0, 0.0, 0.0)) const;
1179 
1186  Eigen::MatrixXd getJacobian(const JointModelGroup* group,
1187  const Eigen::Vector3d& reference_point_position = Eigen::Vector3d(0.0, 0.0, 0.0))
1188  {
1190  return static_cast<const RobotState*>(this)->getJacobian(group, reference_point_position);
1191  }
1192 
1195  void computeVariableVelocity(const JointModelGroup* jmg, Eigen::VectorXd& qdot, const Eigen::VectorXd& twist,
1196  const LinkModel* tip) const;
1197 
1200  void computeVariableVelocity(const JointModelGroup* jmg, Eigen::VectorXd& qdot, const Eigen::VectorXd& twist,
1201  const LinkModel* tip)
1202  {
1204  static_cast<const RobotState*>(this)->computeVariableVelocity(jmg, qdot, twist, tip);
1205  }
1206 
1210  bool integrateVariableVelocity(const JointModelGroup* jmg, const Eigen::VectorXd& qdot, double dt,
1212 
1219  void setVariableValues(const sensor_msgs::msg::JointState& msg)
1220  {
1221  if (!msg.position.empty())
1222  setVariablePositions(msg.name, msg.position);
1223  if (!msg.velocity.empty())
1224  setVariableVelocities(msg.name, msg.velocity);
1225  }
1226 
1230  void setToDefaultValues();
1231 
1233  bool setToDefaultValues(const JointModelGroup* group, const std::string& name);
1234 
1235  bool setToDefaultValues(const std::string& group_name, const std::string& state_name)
1236  {
1237  const JointModelGroup* jmg = getJointModelGroup(group_name);
1238  if (jmg)
1239  return setToDefaultValues(jmg, state_name);
1240  else
1241  return false;
1242  }
1243 
1245  void setToRandomPositions();
1246 
1249 
1252  void setToRandomPositions(const JointModelGroup* group, random_numbers::RandomNumberGenerator& rng);
1253 
1259  void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& seed, double distance);
1260 
1266  void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& seed, double distance,
1267  random_numbers::RandomNumberGenerator& rng);
1268 
1277  const std::vector<double>& distances);
1278 
1287  const std::vector<double>& distances, random_numbers::RandomNumberGenerator& rng);
1288 
1298 
1301  void updateLinkTransforms();
1302 
1304  void update(bool force = false);
1305 
1314  void updateStateWithLinkAt(const std::string& link_name, const Eigen::Isometry3d& transform, bool backward = false)
1315  {
1316  updateStateWithLinkAt(robot_model_->getLinkModel(link_name), transform, backward);
1317  }
1318 
1320  void updateStateWithLinkAt(const LinkModel* link, const Eigen::Isometry3d& transform, bool backward = false);
1321 
1327  const moveit::core::LinkModel* getRigidlyConnectedParentLinkModel(const std::string& frame) const;
1328 
1339  const Eigen::Isometry3d& getGlobalLinkTransform(const std::string& link_name)
1340  {
1341  return getGlobalLinkTransform(robot_model_->getLinkModel(link_name));
1342  }
1343 
1344  const Eigen::Isometry3d& getGlobalLinkTransform(const LinkModel* link)
1345  {
1346  if (!link)
1347  {
1348  throw Exception("Invalid link");
1349  }
1351  return global_link_transforms_[link->getLinkIndex()];
1352  }
1353 
1354  const Eigen::Isometry3d& getGlobalLinkTransform(const std::string& link_name) const
1355  {
1356  return getGlobalLinkTransform(robot_model_->getLinkModel(link_name));
1357  }
1358 
1359  const Eigen::Isometry3d& getGlobalLinkTransform(const LinkModel* link) const
1360  {
1361  if (!link)
1362  {
1363  throw Exception("Invalid link");
1364  }
1365  assert(checkLinkTransforms());
1366  return global_link_transforms_[link->getLinkIndex()];
1367  }
1368 
1379  const Eigen::Isometry3d& getCollisionBodyTransform(const std::string& link_name, std::size_t index)
1380  {
1381  return getCollisionBodyTransform(robot_model_->getLinkModel(link_name), index);
1382  }
1383 
1384  const Eigen::Isometry3d& getCollisionBodyTransform(const LinkModel* link, std::size_t index)
1385  {
1387  return global_collision_body_transforms_[link->getFirstCollisionBodyTransformIndex() + index];
1388  }
1389 
1390  const Eigen::Isometry3d& getCollisionBodyTransform(const std::string& link_name, std::size_t index) const
1391  {
1392  return getCollisionBodyTransform(robot_model_->getLinkModel(link_name), index);
1393  }
1394 
1395  const Eigen::Isometry3d& getCollisionBodyTransform(const LinkModel* link, std::size_t index) const
1396  {
1397  assert(checkCollisionTransforms());
1398  return global_collision_body_transforms_[link->getFirstCollisionBodyTransformIndex() + index];
1399  }
1400 
1401  const Eigen::Isometry3d& getJointTransform(const std::string& joint_name)
1402  {
1403  return getJointTransform(robot_model_->getJointModel(joint_name));
1404  }
1405 
1406  const Eigen::Isometry3d& getJointTransform(const JointModel* joint)
1407  {
1408  const int idx = joint->getJointIndex();
1409  unsigned char& dirty = dirty_joint_transforms_[idx];
1410  if (dirty)
1411  {
1412  joint->computeTransform(position_ + joint->getFirstVariableIndex(), variable_joint_transforms_[idx]);
1413  dirty = 0;
1414  }
1415  return variable_joint_transforms_[idx];
1416  }
1417 
1418  const Eigen::Isometry3d& getJointTransform(const std::string& joint_name) const
1419  {
1420  return getJointTransform(robot_model_->getJointModel(joint_name));
1421  }
1422 
1423  const Eigen::Isometry3d& getJointTransform(const JointModel* joint) const
1424  {
1425  assert(checkJointTransforms(joint));
1426  return variable_joint_transforms_[joint->getJointIndex()];
1427  }
1428 
1429  bool dirtyJointTransform(const JointModel* joint) const
1430  {
1431  return dirty_joint_transforms_[joint->getJointIndex()];
1432  }
1433 
1434  bool dirtyLinkTransforms() const
1435  {
1436  return dirty_link_transforms_;
1437  }
1438 
1440  {
1441  return dirty_link_transforms_ || dirty_collision_body_transforms_;
1442  }
1443 
1445  bool dirty() const
1446  {
1448  }
1449 
1457  double distance(const RobotState& other) const
1458  {
1459  return robot_model_->distance(position_, other.getVariablePositions());
1460  }
1461 
1463  double distance(const RobotState& other, const JointModelGroup* joint_group) const;
1464 
1466  double distance(const RobotState& other, const JointModel* joint) const
1467  {
1468  const int idx = joint->getFirstVariableIndex();
1469  return joint->distance(position_ + idx, other.position_ + idx);
1470  }
1471 
1480  void interpolate(const RobotState& to, double t, RobotState& state) const;
1481 
1491  void interpolate(const RobotState& to, double t, RobotState& state, const JointModelGroup* joint_group) const;
1492 
1502  void interpolate(const RobotState& to, double t, RobotState& state, const JointModel* joint) const
1503  {
1504  const int idx = joint->getFirstVariableIndex();
1505  joint->interpolate(position_ + idx, to.position_ + idx, t, state.position_ + idx);
1506  state.markDirtyJointTransforms(joint);
1507  state.updateMimicJoint(joint);
1508  }
1509 
1510  void enforceBounds();
1511  void enforceBounds(const JointModelGroup* joint_group);
1512  void enforceBounds(const JointModel* joint)
1513  {
1514  enforcePositionBounds(joint);
1515  if (has_velocity_)
1516  enforceVelocityBounds(joint);
1517  }
1519  {
1520  if (joint->enforcePositionBounds(position_ + joint->getFirstVariableIndex()))
1521  {
1522  markDirtyJointTransforms(joint);
1523  updateMimicJoint(joint);
1524  }
1525  }
1526 
1528  void harmonizePositions();
1529  void harmonizePositions(const JointModelGroup* joint_group);
1530  void harmonizePosition(const JointModel* joint)
1531  {
1532  if (joint->harmonizePosition(position_ + joint->getFirstVariableIndex()))
1533  // no need to mark transforms dirty, as the transform hasn't changed
1534  updateMimicJoint(joint);
1535  }
1536 
1538  {
1539  joint->enforceVelocityBounds(velocity_ + joint->getFirstVariableIndex());
1540  }
1541 
1542  bool satisfiesBounds(double margin = 0.0) const;
1543  bool satisfiesBounds(const JointModelGroup* joint_group, double margin = 0.0) const;
1544  bool satisfiesBounds(const JointModel* joint, double margin = 0.0) const
1545  {
1546  return satisfiesPositionBounds(joint, margin) && (!has_velocity_ || satisfiesVelocityBounds(joint, margin));
1547  }
1548  bool satisfiesPositionBounds(const JointModel* joint, double margin = 0.0) const
1549  {
1550  return joint->satisfiesPositionBounds(getJointPositions(joint), margin);
1551  }
1552  bool satisfiesVelocityBounds(const JointModel* joint, double margin = 0.0) const
1553  {
1554  return joint->satisfiesVelocityBounds(getJointVelocities(joint), margin);
1555  }
1556 
1559  std::pair<double, const JointModel*> getMinDistanceToPositionBounds() const;
1560 
1563  std::pair<double, const JointModel*> getMinDistanceToPositionBounds(const JointModelGroup* group) const;
1564 
1567  std::pair<double, const JointModel*>
1568  getMinDistanceToPositionBounds(const std::vector<const JointModel*>& joints) const;
1569 
1576  bool isValidVelocityMove(const RobotState& other, const JointModelGroup* group, double dt) const;
1577 
1594  void attachBody(std::unique_ptr<AttachedBody> attached_body);
1595 
1615  [[deprecated("Deprecated. Pass a unique_ptr instead")]] void attachBody(AttachedBody* attached_body);
1616 
1634  void attachBody(const std::string& id, const Eigen::Isometry3d& pose,
1635  const std::vector<shapes::ShapeConstPtr>& shapes, const EigenSTL::vector_Isometry3d& shape_poses,
1636  const std::set<std::string>& touch_links, const std::string& link_name,
1637  const trajectory_msgs::msg::JointTrajectory& detach_posture = trajectory_msgs::msg::JointTrajectory(),
1639 
1657  void attachBody(const std::string& id, const Eigen::Isometry3d& pose,
1658  const std::vector<shapes::ShapeConstPtr>& shapes, const EigenSTL::vector_Isometry3d& shape_poses,
1659  const std::vector<std::string>& touch_links, const std::string& link_name,
1660  const trajectory_msgs::msg::JointTrajectory& detach_posture = trajectory_msgs::msg::JointTrajectory(),
1662  {
1663  std::set<std::string> touch_links_set(touch_links.begin(), touch_links.end());
1664  attachBody(id, pose, shapes, shape_poses, touch_links_set, link_name, detach_posture, subframe_poses);
1665  }
1666 
1668  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies) const;
1669 
1671  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const JointModelGroup* group) const;
1672 
1674  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const LinkModel* link_model) const;
1675 
1678  bool clearAttachedBody(const std::string& id);
1679 
1681  void clearAttachedBodies(const LinkModel* link);
1682 
1685 
1687  void clearAttachedBodies();
1688 
1690  const AttachedBody* getAttachedBody(const std::string& name) const;
1691 
1693  bool hasAttachedBody(const std::string& id) const;
1694 
1700  void computeAABB(std::vector<double>& aabb) const;
1701 
1704  void computeAABB(std::vector<double>& aabb)
1705  {
1707  static_cast<const RobotState*>(this)->computeAABB(aabb);
1708  }
1709 
1711  random_numbers::RandomNumberGenerator& getRandomNumberGenerator()
1712  {
1713  if (!rng_)
1714  rng_ = new random_numbers::RandomNumberGenerator();
1715  return *rng_;
1716  }
1717 
1723  const Eigen::Isometry3d& getFrameTransform(const std::string& frame_id, bool* frame_found = nullptr);
1724 
1730  const Eigen::Isometry3d& getFrameTransform(const std::string& frame_id, bool* frame_found = nullptr) const;
1731 
1738  const Eigen::Isometry3d& getFrameInfo(const std::string& frame_id, const LinkModel*& robot_link,
1739  bool& frame_found) const;
1740 
1742  bool knowsFrameTransform(const std::string& frame_id) const;
1743 
1751  void getRobotMarkers(visualization_msgs::msg::MarkerArray& arr, const std::vector<std::string>& link_names,
1752  const std_msgs::msg::ColorRGBA& color, const std::string& ns, const rclcpp::Duration& dur,
1753  bool include_attached = false) const;
1754 
1762  void getRobotMarkers(visualization_msgs::msg::MarkerArray& arr, const std::vector<std::string>& link_names,
1763  const std_msgs::msg::ColorRGBA& color, const std::string& ns, const rclcpp::Duration& dur,
1764  bool include_attached = false)
1765  {
1767  static_cast<const RobotState*>(this)->getRobotMarkers(arr, link_names, color, ns, dur, include_attached);
1768  }
1769 
1774  void getRobotMarkers(visualization_msgs::msg::MarkerArray& arr, const std::vector<std::string>& link_names,
1775  bool include_attached = false) const;
1776 
1781  void getRobotMarkers(visualization_msgs::msg::MarkerArray& arr, const std::vector<std::string>& link_names,
1782  bool include_attached = false)
1783  {
1785  static_cast<const RobotState*>(this)->getRobotMarkers(arr, link_names, include_attached);
1786  }
1787 
1788  void printStatePositions(std::ostream& out = std::cout) const;
1789 
1791  void printStatePositionsWithJointLimits(const moveit::core::JointModelGroup* jmg, std::ostream& out = std::cout) const;
1792 
1793  void printStateInfo(std::ostream& out = std::cout) const;
1794 
1795  void printTransforms(std::ostream& out = std::cout) const;
1796 
1797  void printTransform(const Eigen::Isometry3d& transform, std::ostream& out = std::cout) const;
1798 
1799  void printDirtyInfo(std::ostream& out = std::cout) const;
1800 
1801  std::string getStateTreeString() const;
1802 
1809  bool setToIKSolverFrame(Eigen::Isometry3d& pose, const kinematics::KinematicsBaseConstPtr& solver);
1810 
1817  bool setToIKSolverFrame(Eigen::Isometry3d& pose, const std::string& ik_frame);
1818 
1819 private:
1820  void allocMemory();
1821  void initTransforms();
1822  void copyFrom(const RobotState& other);
1823 
1824  void markDirtyJointTransforms(const JointModel* joint)
1825  {
1826  dirty_joint_transforms_[joint->getJointIndex()] = 1;
1827  dirty_link_transforms_ =
1828  dirty_link_transforms_ == nullptr ? joint : robot_model_->getCommonRoot(dirty_link_transforms_, joint);
1829  }
1830 
1831  void markDirtyJointTransforms(const JointModelGroup* group)
1832  {
1833  for (const JointModel* jm : group->getActiveJointModels())
1834  dirty_joint_transforms_[jm->getJointIndex()] = 1;
1835  dirty_link_transforms_ = dirty_link_transforms_ == nullptr ?
1836  group->getCommonRoot() :
1837  robot_model_->getCommonRoot(dirty_link_transforms_, group->getCommonRoot());
1838  }
1839 
1840  void markVelocity();
1841  void markAcceleration();
1842  void markEffort();
1843 
1844  void updateMimicJoint(const JointModel* joint)
1845  {
1846  double v = position_[joint->getFirstVariableIndex()];
1847  for (const JointModel* jm : joint->getMimicRequests())
1848  {
1849  position_[jm->getFirstVariableIndex()] = jm->getMimicFactor() * v + jm->getMimicOffset();
1850  markDirtyJointTransforms(jm);
1851  }
1852  }
1853 
1855  /* use updateMimicJoints() instead, which also marks joints dirty */
1856  [[deprecated]] void updateMimicJoint(const std::vector<const JointModel*>& mim)
1857  {
1858  for (const JointModel* jm : mim)
1859  {
1860  const int fvi = jm->getFirstVariableIndex();
1861  position_[fvi] = jm->getMimicFactor() * position_[jm->getMimic()->getFirstVariableIndex()] + jm->getMimicOffset();
1862  // Only mark joint transform dirty, but not the associated link transform
1863  // as this function is always used in combination of
1864  // updateMimicJoint(group->getMimicJointModels()) + markDirtyJointTransforms(group);
1865  dirty_joint_transforms_[jm->getJointIndex()] = 1;
1866  }
1867  }
1868 
1870  void updateMimicJoints(const JointModelGroup* group)
1871  {
1872  for (const JointModel* jm : group->getMimicJointModels())
1873  {
1874  const int fvi = jm->getFirstVariableIndex();
1875  position_[fvi] = jm->getMimicFactor() * position_[jm->getMimic()->getFirstVariableIndex()] + jm->getMimicOffset();
1876  markDirtyJointTransforms(jm);
1877  }
1878  markDirtyJointTransforms(group);
1879  }
1880 
1881  void updateLinkTransformsInternal(const JointModel* start);
1882 
1883  void getMissingKeys(const std::map<std::string, double>& variable_map,
1884  std::vector<std::string>& missing_variables) const;
1885  void getStateTreeJointString(std::ostream& ss, const JointModel* jm, const std::string& pfx0, bool last) const;
1886 
1888  bool checkJointTransforms(const JointModel* joint) const;
1889 
1891  bool checkLinkTransforms() const;
1892 
1894  bool checkCollisionTransforms() const;
1895 
1896  RobotModelConstPtr robot_model_;
1897  void* memory_;
1898 
1899  double* position_;
1900  double* velocity_;
1901  double* acceleration_;
1902  double* effort_;
1903  bool has_velocity_;
1904  bool has_acceleration_;
1905  bool has_effort_;
1906 
1907  const JointModel* dirty_link_transforms_;
1908  const JointModel* dirty_collision_body_transforms_;
1909 
1910  // All the following transform variables point into aligned memory in memory_
1911  // They are updated lazily, based on the flags in dirty_joint_transforms_
1912  // resp. the pointers dirty_link_transforms_ and dirty_collision_body_transforms_
1913  Eigen::Isometry3d* variable_joint_transforms_;
1914  Eigen::Isometry3d* global_link_transforms_;
1915  Eigen::Isometry3d* global_collision_body_transforms_;
1916  unsigned char* dirty_joint_transforms_;
1917 
1919  std::map<std::string, std::unique_ptr<AttachedBody>> attached_body_map_;
1920 
1923  AttachedBodyCallback attached_body_update_callback_;
1924 
1930  random_numbers::RandomNumberGenerator* rng_;
1931 };
1932 
1934 std::ostream& operator<<(std::ostream& out, const RobotState& s);
1935 } // namespace core
1936 } // namespace moveit
std::function< double(const geometry_msgs::msg::Pose &, const moveit::core::RobotState &, moveit::core::JointModelGroup const *, const std::vector< double > &)> IKCostFn
Signature for a cost function used to evaluate IK solutions.
This may be thrown if unrecoverable errors occur.
Definition: exceptions.h:53
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
unsigned int getActiveVariableCount() const
Get the number of variables that describe the active joints in this joint group. This excludes variab...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
bool satisfiesVelocityBounds(const double *values, double margin=0.0) const
Check if the set of velocities for the variables of this joint are within bounds.
Definition: joint_model.h:311
virtual void computeVariablePositions(const Eigen::Isometry3d &transform, double *joint_values) const =0
Given the transform generated by joint, compute the corresponding joint values. Make sure the passed ...
size_t getJointIndex() const
Get the index of this joint within the robot model.
Definition: joint_model.h:222
size_t getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
Definition: joint_model.h:216
virtual bool harmonizePosition(double *values, const Bounds &other_bounds) const
Definition: joint_model.cpp:93
virtual void interpolate(const double *from, const double *to, const double t, double *state) const =0
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state....
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Definition: joint_model.h:210
virtual double distance(const double *value1, const double *value2) const =0
Compute the distance between two joint states of the same model (represented by the variable values)
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
Definition: joint_model.h:320
virtual void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const =0
Given the joint values for a joint, compute the corresponding transform. The computed transform is gu...
bool enforcePositionBounds(double *values) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
Definition: joint_model.h:292
bool satisfiesPositionBounds(const double *values, double margin=0.0) const
Check if the set of values for the variables of this joint are within bounds.
Definition: joint_model.h:280
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
int getFirstCollisionBodyTransformIndex() const
Definition: link_model.h:97
size_t getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
Definition: link_model.h:92
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setJointGroupActivePositions(const std::string &joint_group_name, const std::vector< double > &gstate)
Given positions for the variables of active joints that make up a group, in the order found in the gr...
Definition: robot_state.h:660
const double * getJointEffort(const JointModel *joint) const
Definition: robot_state.h:592
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void setVariableAcceleration(const std::string &variable, double value)
Set the acceleration of a variable. If an unknown variable name is specified, an exception is thrown.
Definition: robot_state.h:381
void zeroVelocities()
Set all velocities to 0.0.
const Eigen::Isometry3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index) const
Definition: robot_state.h:1390
RobotState & operator=(const RobotState &other)
Copy operator.
const double * getJointPositions(const JointModel *joint) const
Definition: robot_state.h:562
double getVariableVelocity(int index) const
Get the velocity of a particular variable. The variable is specified by its index....
Definition: robot_state.h:304
void setVariableAcceleration(int index, double value)
Set the acceleration of a single variable. The variable is specified by its index (a value associated...
Definition: robot_state.h:388
void copyJointGroupVelocities(const std::string &joint_group_name, Eigen::VectorXd &values) const
For a given group, copy the velocity values of the variables that make up the group into another loca...
Definition: robot_state.h:828
void setJointEfforts(const JointModel *joint, const double *effort)
void interpolate(const RobotState &to, double t, RobotState &state, const JointModel *joint) const
Definition: robot_state.h:1502
void attachBody(const std::string &id, const Eigen::Isometry3d &pose, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &shape_poses, const std::vector< std::string > &touch_links, const std::string &link_name, const trajectory_msgs::msg::JointTrajectory &detach_posture=trajectory_msgs::msg::JointTrajectory(), const moveit::core::FixedTransformsMap &subframe_poses=moveit::core::FixedTransformsMap())
Add an attached body to a link.
Definition: robot_state.h:1657
void enforceBounds(const JointModel *joint)
Definition: robot_state.h:1512
double getVariableEffort(const std::string &variable) const
Get the effort of a particular variable. An exception is thrown if the variable is not known.
Definition: robot_state.h:486
bool satisfiesVelocityBounds(const JointModel *joint, double margin=0.0) const
Definition: robot_state.h:1552
void setAttachedBodyUpdateCallback(const AttachedBodyCallback &callback)
void setVariableAccelerations(const std::vector< double > &acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
Definition: robot_state.h:359
void setJointGroupAccelerations(const std::string &joint_group_name, const std::vector< double > &gstate)
Given accelerations for the variables that make up a group, in the order found in the group (includin...
Definition: robot_state.h:857
void setJointVelocities(const JointModel *joint, const double *velocity)
Definition: robot_state.h:549
double getVariableAcceleration(const std::string &variable) const
Get the acceleration of a particular variable. An exception is thrown if the variable is not known.
Definition: robot_state.h:395
double getVariableAcceleration(int index) const
Get the acceleration of a particular variable. The variable is specified by its index....
Definition: robot_state.h:403
void printTransforms(std::ostream &out=std::cout) const
void setVariableEffort(const std::string &variable, double value)
Set the effort of a variable. If an unknown variable name is specified, an exception is thrown.
Definition: robot_state.h:472
const Eigen::Isometry3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1379
void printTransform(const Eigen::Isometry3d &transform, std::ostream &out=std::cout) const
const double * getVariableEffort() const
Get const raw access to the effort of the variables that make up this state. The values are in the sa...
Definition: robot_state.h:436
const double * getJointEffort(const std::string &joint_name) const
Definition: robot_state.h:587
void setJointGroupAccelerations(const std::string &joint_group_name, const Eigen::VectorXd &values)
Given accelerations for the variables that make up a group, in the order found in the group (includin...
Definition: robot_state.h:877
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
Definition: robot_state.h:122
void copyJointGroupPositions(const std::string &joint_group_name, double *gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
Definition: robot_state.h:704
void copyJointGroupAccelerations(const std::string &joint_group_name, double *gstate) const
For a given group, copy the acceleration values of the variables that make up the group into another ...
Definition: robot_state.h:904
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1339
void updateStateWithLinkAt(const std::string &link_name, const Eigen::Isometry3d &transform, bool backward=false)
Update the state after setting a particular link to the input global transform pose.
Definition: robot_state.h:1314
void copyJointGroupVelocities(const std::string &joint_group_name, double *gstate) const
For a given group, copy the velocity values of the variables that make up the group into another loca...
Definition: robot_state.h:804
bool getJacobian(const JointModelGroup *group, const LinkModel *link, const Eigen::Vector3d &reference_point_position, Eigen::MatrixXd &jacobian, bool use_quaternion_representation=false) const
Compute the Jacobian with reference to a particular point on a given link, for a specified group.
bool getJacobian(const JointModelGroup *group, const LinkModel *link, const Eigen::Vector3d &reference_point_position, Eigen::MatrixXd &jacobian, bool use_quaternion_representation=false)
Compute the Jacobian with reference to a particular point on a given link, for a specified group.
Definition: robot_state.h:1163
const double * getJointPositions(const std::string &joint_name) const
Definition: robot_state.h:557
double getVariablePosition(int index) const
Get the position of a particular variable. The variable is specified by its index....
Definition: robot_state.h:215
std::pair< double, const JointModel * > getMinDistanceToPositionBounds() const
Get the minimm distance from this state to the bounds. The minimum distance and the joint for which t...
void copyJointGroupVelocities(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the velocity values of the variables that make up the group into another loca...
Definition: robot_state.h:791
void setVariablePosition(int index, double value)
Set the position of a single variable. The variable is specified by its index (a value associated by ...
Definition: robot_state.h:195
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
Definition: robot_state.h:229
void getRobotMarkers(visualization_msgs::msg::MarkerArray &arr, const std::vector< std::string > &link_names, const std_msgs::msg::ColorRGBA &color, const std::string &ns, const rclcpp::Duration &dur, bool include_attached=false)
Get a MarkerArray that fully describes the robot markers for a given robot. Update the state first.
Definition: robot_state.h:1762
void setVariableEffort(int index, double value)
Set the effort of a single variable. The variable is specified by its index (a value associated by th...
Definition: robot_state.h:479
void setVariableEffort(const std::vector< double > &effort)
Given an array with effort values for all variables, set those values as the effort in this state.
Definition: robot_state.h:454
void copyJointGroupVelocities(const JointModelGroup *group, std::vector< double > &gstate) const
For a given group, copy the velocity values of the variables that make up the group into another loca...
Definition: robot_state.h:814
void setVariableVelocity(const std::string &variable, double value)
Set the velocity of a variable. If an unknown variable name is specified, an exception is thrown.
Definition: robot_state.h:282
double getVariableVelocity(const std::string &variable) const
Get the velocity of a particular variable. An exception is thrown if the variable is not known.
Definition: robot_state.h:296
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
const JointModel * getJointModel(const std::string &joint) const
Get the model of a particular joint.
Definition: robot_state.h:128
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
Definition: robot_state.h:1401
void setJointGroupAccelerations(const std::string &joint_group_name, const double *gstate)
Given accelerations for the variables that make up a group, in the order found in the group (includin...
Definition: robot_state.h:848
Eigen::MatrixXd getJacobian(const JointModelGroup *group, const Eigen::Vector3d &reference_point_position=Eigen::Vector3d(0.0, 0.0, 0.0))
Compute the Jacobian with reference to the last link of a specified group. If the group is not a chai...
Definition: robot_state.h:1186
void setJointGroupVelocities(const std::string &joint_group_name, const double *gstate)
Given velocities for the variables that make up a group, in the order found in the group (including v...
Definition: robot_state.h:748
void computeVariableVelocity(const JointModelGroup *jmg, Eigen::VectorXd &qdot, const Eigen::VectorXd &twist, const LinkModel *tip) const
Given a twist for a particular link (tip), compute the corresponding velocity for every variable and ...
const double * getJointVelocities(const JointModel *joint) const
Definition: robot_state.h:572
void getRobotMarkers(visualization_msgs::msg::MarkerArray &arr, const std::vector< std::string > &link_names, bool include_attached=false)
Get a MarkerArray that fully describes the robot markers for a given robot. Update the state first.
Definition: robot_state.h:1781
bool hasAccelerations() const
By default, if accelerations are never set or initialized, the state remembers that there are no acce...
Definition: robot_state.h:322
void setVariablePosition(const std::string &variable, double value)
Set the position of a single variable. An exception is thrown if the variable name is not known.
Definition: robot_state.h:188
void computeAABB(std::vector< double > &aabb) const
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx,...
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:605
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
Definition: robot_state.h:691
bool clearAttachedBody(const std::string &id)
Remove the attached body named id. Return false if the object was not found (and thus not removed)....
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
Definition: robot_state.h:104
void harmonizePositions()
Call harmonizePosition() for all joints / all joints in group / given joint.
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
Definition: robot_state.h:253
void setJointGroupVelocities(const std::string &joint_group_name, const Eigen::VectorXd &values)
Given velocities for the variables that make up a group, in the order found in the group (including v...
Definition: robot_state.h:777
bool dirtyCollisionBodyTransforms() const
Definition: robot_state.h:1439
const Eigen::Isometry3d & getJointTransform(const JointModel *joint)
Definition: robot_state.h:1406
void zeroAccelerations()
Set all accelerations to 0.0.
bool isValidVelocityMove(const RobotState &other, const JointModelGroup *group, double dt) const
Check that the time to move between two waypoints is sufficient given velocity limits and time step.
const double * getVariablePositions() const
Get a raw pointer to the positions of the variables stored in this state.
Definition: robot_state.h:154
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name) const
Definition: robot_state.h:1354
bool setFromDiffIK(const JointModelGroup *group, const Eigen::VectorXd &twist, const std::string &tip, double dt, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn())
Set the joint values from a Cartesian velocity applied during a time dt.
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
Definition: robot_state.h:147
void printStatePositionsWithJointLimits(const moveit::core::JointModelGroup *jmg, std::ostream &out=std::cout) const
Output to console the current state of the robot's joint limits.
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
Definition: robot_state.h:134
void setVariableVelocity(int index, double value)
Set the velocity of a single variable. The variable is specified by its index (a value associated by ...
Definition: robot_state.h:289
const double * getJointVelocities(const std::string &joint_name) const
Definition: robot_state.h:567
void dropDynamics()
Reduce RobotState to kinematic information (remove velocity, acceleration and effort,...
bool dirtyJointTransform(const JointModel *joint) const
Definition: robot_state.h:1429
void setToRandomPositionsNearBy(const JointModelGroup *group, const RobotState &seed, double distance)
Set all joints in group to random values near the value in seed. distance is the maximum amount each ...
bool dirty() const
Returns true if anything in this state is dirty.
Definition: robot_state.h:1445
bool hasEffort() const
By default, if effort is never set or initialized, the state remembers that there is no effort set....
Definition: robot_state.h:420
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
void setJointGroupActivePositions(const std::string &joint_group_name, const Eigen::VectorXd &values)
Given positions for the variables of active joints that make up a group, in the order found in the gr...
Definition: robot_state.h:678
double * getVariableVelocities()
Get raw access to the velocities of the variables that make up this state. The values are in the same...
Definition: robot_state.h:236
void copyJointGroupPositions(const std::string &joint_group_name, Eigen::VectorXd &values) const
For a given group, copy the position values of the variables that make up the group into another loca...
Definition: robot_state.h:728
double * getVariableEffort()
Get raw access to the effort of the variables that make up this state. The values are in the same ord...
Definition: robot_state.h:428
void interpolate(const RobotState &to, double t, RobotState &state) const
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
Definition: robot_state.h:1457
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name) const
Definition: robot_state.h:1418
void setJointGroupAccelerations(const JointModelGroup *group, const std::vector< double > &gstate)
Given accelerations for the variables that make up a group, in the order found in the group (includin...
Definition: robot_state.h:866
bool satisfiesPositionBounds(const JointModel *joint, double margin=0.0) const
Definition: robot_state.h:1548
std::string getStateTreeString() const
void copyJointGroupAccelerations(const JointModelGroup *group, std::vector< double > &gstate) const
For a given group, copy the acceleration values of the variables that make up the group into another ...
Definition: robot_state.h:914
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void setVariablePositions(const std::vector< double > &position)
It is assumed positions is an array containing the new positions for all variables in this state....
Definition: robot_state.h:167
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
bool satisfiesBounds(double margin=0.0) const
const double * getJointAccelerations(const JointModel *joint) const
Definition: robot_state.h:582
void setVariableEffort(const double *effort)
Given an array with effort values for all variables, set those values as the effort in this state.
Definition: robot_state.h:445
void setVariableVelocities(const std::vector< double > &velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
Definition: robot_state.h:261
void setJointGroupVelocities(const JointModelGroup *group, const std::vector< double > &gstate)
Given velocities for the variables that make up a group, in the order found in the group (including v...
Definition: robot_state.h:766
void setJointGroupActivePositions(const JointModelGroup *group, const std::vector< double > &gstate)
Given positions for the variables of active joints that make up a group, in the order found in the gr...
bool dirtyLinkTransforms() const
Definition: robot_state.h:1434
void setJointPositions(const JointModel *joint, const double *position)
Definition: robot_state.h:530
void printStateInfo(std::ostream &out=std::cout) const
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
Definition: robot_state.h:207
void update(bool force=false)
Update all transforms.
void setJointGroupPositions(const std::string &joint_group_name, const std::vector< double > &gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:614
void dropAccelerations()
Remove accelerations from this state (this differs from setting them to zero)
const Eigen::Isometry3d & getGlobalLinkTransform(const LinkModel *link)
Definition: robot_state.h:1344
void getRobotMarkers(visualization_msgs::msg::MarkerArray &arr, const std::vector< std::string > &link_names, const std_msgs::msg::ColorRGBA &color, const std::string &ns, const rclcpp::Duration &dur, bool include_attached=false) const
Get a MarkerArray that fully describes the robot markers for a given robot.
void setJointGroupVelocities(const std::string &joint_group_name, const std::vector< double > &gstate)
Given velocities for the variables that make up a group, in the order found in the group (including v...
Definition: robot_state.h:757
void setJointGroupPositions(const JointModelGroup *group, const std::vector< double > &gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:626
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return nullptr if not found.
bool setFromIKSubgroups(const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, const std::vector< std::vector< double >> &consistency_limits, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
setFromIK for multiple poses and tips (end effectors) when no solver exists for the jmg that can solv...
const double * getVariableAccelerations() const
Get const raw access to the accelerations of the variables that make up this state....
Definition: robot_state.h:338
bool setToIKSolverFrame(Eigen::Isometry3d &pose, const kinematics::KinematicsBaseConstPtr &solver)
Transform pose from the robot model's base frame to the reference frame of the IK solver.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
const Eigen::Isometry3d & getCollisionBodyTransform(const LinkModel *link, std::size_t index) const
Definition: robot_state.h:1395
void printStatePositions(std::ostream &out=std::cout) const
std::size_t getVariableCount() const
Get the number of variables that make up this state.
Definition: robot_state.h:110
void printDirtyInfo(std::ostream &out=std::cout) const
void copyJointGroupPositions(const JointModelGroup *group, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
Definition: robot_state.h:714
void setVariableAccelerations(const double *acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
Definition: robot_state.h:348
double * getVariableAccelerations()
Get raw access to the accelerations of the variables that make up this state. The values are in the s...
Definition: robot_state.h:330
void setJointPositions(const std::string &joint_name, const std::vector< double > &position)
Definition: robot_state.h:520
void copyJointGroupAccelerations(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the acceleration values of the variables that make up the group into another ...
Definition: robot_state.h:891
RobotState(const RobotModelConstPtr &robot_model)
A state can be constructed from a specified robot model. No values are initialized....
Definition: robot_state.cpp:60
double computeCartesianPath(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, const LinkModel *link, const Eigen::Vector3d &direction, bool global_reference_frame, double distance, double max_step, double jump_threshold_factor, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular gr...
void dropEffort()
Remove effort values from this state (this differs from setting them to zero)
bool knowsFrameTransform(const std::string &frame_id) const
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
bool integrateVariableVelocity(const JointModelGroup *jmg, const Eigen::VectorXd &qdot, double dt, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn())
Given the velocities for the variables in this group (qdot) and an amount of time (dt),...
const double * getJointAccelerations(const std::string &joint_name) const
Definition: robot_state.h:577
bool setToDefaultValues(const std::string &group_name, const std::string &state_name)
Definition: robot_state.h:1235
const Eigen::Isometry3d & getGlobalLinkTransform(const LinkModel *link) const
Definition: robot_state.h:1359
double getVariableEffort(int index) const
Get the effort of a particular variable. The variable is specified by its index. No checks are perfor...
Definition: robot_state.h:494
void computeAABB(std::vector< double > &aabb)
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx,...
Definition: robot_state.h:1704
void setVariableValues(const sensor_msgs::msg::JointState &msg)
Definition: robot_state.h:1219
void enforcePositionBounds(const JointModel *joint)
Definition: robot_state.h:1518
bool hasAttachedBody(const std::string &id) const
Check if an attached body named id exists in this state.
double distance(const RobotState &other, const JointModel *joint) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
Definition: robot_state.h:1466
void setJointPositions(const std::string &joint_name, const Eigen::Isometry3d &transform)
Definition: robot_state.h:537
void copyJointGroupAccelerations(const std::string &joint_group_name, Eigen::VectorXd &values) const
For a given group, copy the acceleration values of the variables that make up the group into another ...
Definition: robot_state.h:928
void enforceVelocityBounds(const JointModel *joint)
Definition: robot_state.h:1537
const Eigen::Isometry3d & getCollisionBodyTransform(const LinkModel *link, std::size_t index)
Definition: robot_state.h:1384
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
Definition: robot_state.h:1711
void setJointGroupPositions(const std::string &joint_group_name, const Eigen::VectorXd &values)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:638
void setJointPositions(const JointModel *joint, const std::vector< double > &position)
Definition: robot_state.h:525
void setJointPositions(const JointModel *joint, const Eigen::Isometry3d &transform)
Definition: robot_state.h:542
void invertVelocity()
Invert velocity if present.
const Eigen::Isometry3d & getFrameInfo(const std::string &frame_id, const LinkModel *&robot_link, bool &frame_found) const
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void harmonizePosition(const JointModel *joint)
Definition: robot_state.h:1530
void clearAttachedBodies()
Clear all attached bodies. This calls delete on the AttachedBody instances, if needed.
void dropVelocities()
Remove velocities from this state (this differs from setting them to zero)
void zeroEffort()
Set all effort values to 0.0.
const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const std::string &frame) const
Get the latest link upwards the kinematic tree which is only connected via fixed joints.
bool satisfiesBounds(const JointModel *joint, double margin=0.0) const
Definition: robot_state.h:1544
void updateCollisionBodyTransforms()
Update the transforms for the collision bodies. This call is needed before calling collision checking...
bool setFromIK(const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, const std::vector< std::vector< double >> &consistency_limits, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Warning: This function inefficiently copies all transforms around. If the group consists of a set of ...
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
void computeVariableVelocity(const JointModelGroup *jmg, Eigen::VectorXd &qdot, const Eigen::VectorXd &twist, const LinkModel *tip)
Given a twist for a particular link (tip), compute the corresponding velocity for every variable and ...
Definition: robot_state.h:1200
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up this state, in the order they are stored in memory.
Definition: robot_state.h:116
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:515
const Eigen::Isometry3d & getJointTransform(const JointModel *joint) const
Definition: robot_state.h:1423
const double * getVariableVelocities() const
Get const access to the velocities of the variables that make up this state. The values are in the sa...
Definition: robot_state.h:244
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
Definition: robot_state.h:70
MOVEIT_CLASS_FORWARD(JointModelGroup)
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
Definition: transforms.h:53
std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
Definition: attached_body.h:51
Main namespace for MoveIt.
Definition: exceptions.h:43
frame_id
Definition: pick.py:63
name
Definition: setup.py:7
Definition: world.h:49
A set of options for the kinematics solver.