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 #ifndef MOVEIT_CORE_ROBOT_STATE_
39 #define MOVEIT_CORE_ROBOT_STATE_
40 
43 #include <sensor_msgs/JointState.h>
44 #include <visualization_msgs/MarkerArray.h>
45 #include <std_msgs/ColorRGBA.h>
46 #include <geometry_msgs/Twist.h>
47 #include <cassert>
48 
49 #include <boost/assert.hpp>
50 
51 namespace moveit
52 {
53 namespace core
54 {
55 MOVEIT_CLASS_FORWARD(RobotState);
56 
61 typedef boost::function<bool(RobotState* robot_state, const JointModelGroup* joint_group,
62  const double* joint_group_variable_values)>
64 
71 {
72  double factor;
73  double revolute; // Radians
74  double prismatic; // Meters
75 
76  explicit JumpThreshold() : factor(0.0), revolute(0.0), prismatic(0.0)
77  {
78  }
79 
80  explicit JumpThreshold(double jt_factor) : JumpThreshold()
81  {
82  factor = jt_factor;
83  }
84 
85  explicit JumpThreshold(double jt_revolute, double jt_prismatic) : JumpThreshold()
86  {
87  revolute = jt_revolute; // Radians
88  prismatic = jt_prismatic; // Meters
89  }
90 };
91 
95 struct MaxEEFStep
96 {
97  MaxEEFStep(double translation = 0.0, double rotation = 0.0) : translation(translation), rotation(rotation)
98  {
99  }
100 
101  double translation; // Meters
102  double rotation; // Radians
103 };
104 
123 {
124 public:
127  RobotState(const RobotModelConstPtr& robot_model);
128  ~RobotState();
129 
131  RobotState(const RobotState& other);
132 
134  RobotState& operator=(const RobotState& other);
135 
137  const RobotModelConstPtr& getRobotModel() const
138  {
139  return robot_model_;
140  }
141 
143  std::size_t getVariableCount() const
144  {
145  return robot_model_->getVariableCount();
146  }
147 
149  const std::vector<std::string>& getVariableNames() const
150  {
151  return robot_model_->getVariableNames();
152  }
153 
155  const LinkModel* getLinkModel(const std::string& link) const
156  {
157  return robot_model_->getLinkModel(link);
158  }
159 
161  const JointModel* getJointModel(const std::string& joint) const
162  {
163  return robot_model_->getJointModel(joint);
164  }
165 
167  const JointModelGroup* getJointModelGroup(const std::string& group) const
168  {
169  return robot_model_->getJointModelGroup(group);
170  }
171 
181  {
182  return position_;
183  }
184 
187  const double* getVariablePositions() const
188  {
189  return position_;
190  }
191 
195  void setVariablePositions(const double* position);
196 
200  void setVariablePositions(const std::vector<double>& position)
201  {
202  assert(robot_model_->getVariableCount() <= position.size()); // checked only in debug mode
203  setVariablePositions(&position[0]);
204  }
205 
208  void setVariablePositions(const std::map<std::string, double>& variable_map);
209 
212  void setVariablePositions(const std::map<std::string, double>& variable_map,
213  std::vector<std::string>& missing_variables);
214 
217  void setVariablePositions(const std::vector<std::string>& variable_names,
218  const std::vector<double>& variable_position);
219 
221  void setVariablePosition(const std::string& variable, double value)
222  {
223  setVariablePosition(robot_model_->getVariableIndex(variable), value);
224  }
225 
228  void setVariablePosition(int index, double value)
229  {
230  position_[index] = value;
231  const JointModel* jm = robot_model_->getJointOfVariable(index);
232  if (jm)
233  {
234  markDirtyJointTransforms(jm);
235  updateMimicJoint(jm);
236  }
237  }
238 
240  double getVariablePosition(const std::string& variable) const
241  {
242  return position_[robot_model_->getVariableIndex(variable)];
243  }
244 
248  double getVariablePosition(int index) const
249  {
250  return position_[index];
251  }
252 
262  bool hasVelocities() const
263  {
264  return has_velocity_;
265  }
266 
270  {
271  markVelocity();
272  return velocity_;
273  }
274 
277  const double* getVariableVelocities() const
278  {
279  return velocity_;
280  }
281 
283  void zeroVelocities();
284 
286  void setVariableVelocities(const double* velocity)
287  {
288  has_velocity_ = true;
289  // assume everything is in order in terms of array lengths (for efficiency reasons)
290  memcpy(velocity_, velocity, robot_model_->getVariableCount() * sizeof(double));
291  }
292 
294  void setVariableVelocities(const std::vector<double>& velocity)
295  {
296  assert(robot_model_->getVariableCount() <= velocity.size()); // checked only in debug mode
297  setVariableVelocities(&velocity[0]);
298  }
299 
302  void setVariableVelocities(const std::map<std::string, double>& variable_map);
303 
306  void setVariableVelocities(const std::map<std::string, double>& variable_map,
307  std::vector<std::string>& missing_variables);
308 
311  void setVariableVelocities(const std::vector<std::string>& variable_names,
312  const std::vector<double>& variable_velocity);
313 
315  void setVariableVelocity(const std::string& variable, double value)
316  {
317  setVariableVelocity(robot_model_->getVariableIndex(variable), value);
318  }
319 
322  void setVariableVelocity(int index, double value)
323  {
324  markVelocity();
325  velocity_[index] = value;
326  }
327 
329  double getVariableVelocity(const std::string& variable) const
330  {
331  return velocity_[robot_model_->getVariableIndex(variable)];
332  }
333 
337  double getVariableVelocity(int index) const
338  {
339  return velocity_[index];
340  }
341 
343  void dropVelocities();
344 
355  bool hasAccelerations() const
356  {
357  return has_acceleration_;
358  }
359 
364  {
365  markAcceleration();
366  return acceleration_;
367  }
368 
371  const double* getVariableAccelerations() const
372  {
373  return acceleration_;
374  }
375 
377  void zeroAccelerations();
378 
381  void setVariableAccelerations(const double* acceleration)
382  {
383  has_acceleration_ = true;
384  has_effort_ = false;
385 
386  // assume everything is in order in terms of array lengths (for efficiency reasons)
387  memcpy(acceleration_, acceleration, robot_model_->getVariableCount() * sizeof(double));
388  }
389 
392  void setVariableAccelerations(const std::vector<double>& acceleration)
393  {
394  assert(robot_model_->getVariableCount() <= acceleration.size()); // checked only in debug mode
395  setVariableAccelerations(&acceleration[0]);
396  }
397 
400  void setVariableAccelerations(const std::map<std::string, double>& variable_map);
401 
405  void setVariableAccelerations(const std::map<std::string, double>& variable_map,
406  std::vector<std::string>& missing_variables);
407 
410  void setVariableAccelerations(const std::vector<std::string>& variable_names,
411  const std::vector<double>& variable_acceleration);
412 
414  void setVariableAcceleration(const std::string& variable, double value)
415  {
416  setVariableAcceleration(robot_model_->getVariableIndex(variable), value);
417  }
418 
421  void setVariableAcceleration(int index, double value)
422  {
423  markAcceleration();
424  acceleration_[index] = value;
425  }
426 
428  double getVariableAcceleration(const std::string& variable) const
429  {
430  return acceleration_[robot_model_->getVariableIndex(variable)];
431  }
432 
436  double getVariableAcceleration(int index) const
437  {
438  return acceleration_[index];
439  }
440 
442  void dropAccelerations();
443 
453  bool hasEffort() const
454  {
455  return has_effort_;
456  }
457 
462  {
463  markEffort();
464  return effort_;
465  }
466 
469  const double* getVariableEffort() const
470  {
471  return effort_;
472  }
473 
475  void zeroEffort();
476 
478  void setVariableEffort(const double* effort)
479  {
480  has_effort_ = true;
481  has_acceleration_ = false;
482  // assume everything is in order in terms of array lengths (for efficiency reasons)
483  memcpy(effort_, effort, robot_model_->getVariableCount() * sizeof(double));
484  }
485 
487  void setVariableEffort(const std::vector<double>& effort)
488  {
489  assert(robot_model_->getVariableCount() <= effort.size()); // checked only in debug mode
490  setVariableEffort(&effort[0]);
491  }
492 
494  void setVariableEffort(const std::map<std::string, double>& variable_map);
495 
498  void setVariableEffort(const std::map<std::string, double>& variable_map,
499  std::vector<std::string>& missing_variables);
500 
502  void setVariableEffort(const std::vector<std::string>& variable_names,
503  const std::vector<double>& variable_acceleration);
504 
506  void setVariableEffort(const std::string& variable, double value)
507  {
508  setVariableEffort(robot_model_->getVariableIndex(variable), value);
509  }
510 
513  void setVariableEffort(int index, double value)
514  {
515  markEffort();
516  effort_[index] = value;
517  }
518 
520  double getVariableEffort(const std::string& variable) const
521  {
522  return effort_[robot_model_->getVariableIndex(variable)];
523  }
524 
528  double getVariableEffort(int index) const
529  {
530  return effort_[index];
531  }
532 
534  void dropEffort();
535 
537  void dropDynamics();
538 
540  void invertVelocity();
541 
549  void setJointPositions(const std::string& joint_name, const double* position)
550  {
551  setJointPositions(robot_model_->getJointModel(joint_name), position);
552  }
553 
554  void setJointPositions(const std::string& joint_name, const std::vector<double>& position)
555  {
556  setJointPositions(robot_model_->getJointModel(joint_name), &position[0]);
557  }
558 
559  void setJointPositions(const JointModel* joint, const std::vector<double>& position)
560  {
561  setJointPositions(joint, &position[0]);
562  }
563 
564  void setJointPositions(const JointModel* joint, const double* position)
565  {
566  memcpy(position_ + joint->getFirstVariableIndex(), position, joint->getVariableCount() * sizeof(double));
567  markDirtyJointTransforms(joint);
568  updateMimicJoint(joint);
569  }
570 
571  void setJointPositions(const std::string& joint_name, const Eigen::Isometry3d& transform)
572  {
573  setJointPositions(robot_model_->getJointModel(joint_name), transform);
574  }
575 
576  void setJointPositions(const JointModel* joint, const Eigen::Isometry3d& transform)
577  {
578  joint->computeVariablePositions(transform, position_ + joint->getFirstVariableIndex());
579  markDirtyJointTransforms(joint);
580  updateMimicJoint(joint);
581  }
582 
583  void setJointVelocities(const JointModel* joint, const double* velocity)
584  {
585  has_velocity_ = true;
586  memcpy(velocity_ + joint->getFirstVariableIndex(), velocity, joint->getVariableCount() * sizeof(double));
587  }
588 
589  void setJointEfforts(const JointModel* joint, const double* effort);
590 
591  const double* getJointPositions(const std::string& joint_name) const
592  {
593  return getJointPositions(robot_model_->getJointModel(joint_name));
594  }
595 
596  const double* getJointPositions(const JointModel* joint) const
597  {
598  return position_ + joint->getFirstVariableIndex();
599  }
600 
601  const double* getJointVelocities(const std::string& joint_name) const
602  {
603  return getJointVelocities(robot_model_->getJointModel(joint_name));
604  }
605 
606  const double* getJointVelocities(const JointModel* joint) const
607  {
608  return velocity_ + joint->getFirstVariableIndex();
609  }
610 
611  const double* getJointAccelerations(const std::string& joint_name) const
612  {
613  return getJointAccelerations(robot_model_->getJointModel(joint_name));
614  }
615 
616  const double* getJointAccelerations(const JointModel* joint) const
617  {
618  return acceleration_ + joint->getFirstVariableIndex();
619  }
620 
621  const double* getJointEffort(const std::string& joint_name) const
622  {
623  return getJointEffort(robot_model_->getJointModel(joint_name));
624  }
625 
626  const double* getJointEffort(const JointModel* joint) const
627  {
628  return effort_ + joint->getFirstVariableIndex();
629  }
630 
640  void setJointGroupPositions(const std::string& joint_group_name, const double* gstate)
641  {
642  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
643  if (jmg)
644  setJointGroupPositions(jmg, gstate);
645  }
646 
650  void setJointGroupPositions(const std::string& joint_group_name, const std::vector<double>& gstate)
651  {
652  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
653  if (jmg)
654  setJointGroupPositions(jmg, &gstate[0]);
655  }
656 
660  void setJointGroupPositions(const JointModelGroup* group, const std::vector<double>& gstate)
661  {
662  setJointGroupPositions(group, &gstate[0]);
663  }
664 
668  void setJointGroupPositions(const JointModelGroup* group, const double* gstate);
669 
673  void setJointGroupPositions(const std::string& joint_group_name, const Eigen::VectorXd& values)
674  {
675  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
676  if (jmg)
677  setJointGroupPositions(jmg, values);
678  }
679 
683  void setJointGroupPositions(const JointModelGroup* group, const Eigen::VectorXd& values);
684 
688  void copyJointGroupPositions(const std::string& joint_group_name, std::vector<double>& gstate) const
689  {
690  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
691  if (jmg)
692  {
693  gstate.resize(jmg->getVariableCount());
694  copyJointGroupPositions(jmg, &gstate[0]);
695  }
696  }
697 
701  void copyJointGroupPositions(const std::string& joint_group_name, double* gstate) const
702  {
703  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
704  if (jmg)
705  copyJointGroupPositions(jmg, gstate);
706  }
707 
711  void copyJointGroupPositions(const JointModelGroup* group, std::vector<double>& gstate) const
712  {
713  gstate.resize(group->getVariableCount());
714  copyJointGroupPositions(group, &gstate[0]);
715  }
716 
720  void copyJointGroupPositions(const JointModelGroup* group, double* gstate) const;
721 
725  void copyJointGroupPositions(const std::string& joint_group_name, Eigen::VectorXd& values) const
726  {
727  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
728  if (jmg)
729  copyJointGroupPositions(jmg, values);
730  }
731 
735  void copyJointGroupPositions(const JointModelGroup* group, Eigen::VectorXd& values) const;
736 
746  void setJointGroupVelocities(const std::string& joint_group_name, const double* gstate)
747  {
748  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
749  if (jmg)
750  setJointGroupVelocities(jmg, gstate);
751  }
752 
756  void setJointGroupVelocities(const std::string& joint_group_name, const std::vector<double>& gstate)
757  {
758  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
759  if (jmg)
760  setJointGroupVelocities(jmg, &gstate[0]);
761  }
762 
766  void setJointGroupVelocities(const JointModelGroup* group, const std::vector<double>& gstate)
767  {
768  setJointGroupVelocities(group, &gstate[0]);
769  }
770 
774  void setJointGroupVelocities(const JointModelGroup* group, const double* gstate);
775 
779  void setJointGroupVelocities(const std::string& joint_group_name, const Eigen::VectorXd& values)
780  {
781  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
782  if (jmg)
783  setJointGroupVelocities(jmg, values);
784  }
785 
789  void setJointGroupVelocities(const JointModelGroup* group, const Eigen::VectorXd& values);
790 
794  void copyJointGroupVelocities(const std::string& joint_group_name, std::vector<double>& gstate) const
795  {
796  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
797  if (jmg)
798  {
799  gstate.resize(jmg->getVariableCount());
800  copyJointGroupVelocities(jmg, &gstate[0]);
801  }
802  }
803 
807  void copyJointGroupVelocities(const std::string& joint_group_name, double* gstate) const
808  {
809  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
810  if (jmg)
811  copyJointGroupVelocities(jmg, gstate);
812  }
813 
817  void copyJointGroupVelocities(const JointModelGroup* group, std::vector<double>& gstate) const
818  {
819  gstate.resize(group->getVariableCount());
820  copyJointGroupVelocities(group, &gstate[0]);
821  }
822 
826  void copyJointGroupVelocities(const JointModelGroup* group, double* gstate) const;
827 
831  void copyJointGroupVelocities(const std::string& joint_group_name, Eigen::VectorXd& values) const
832  {
833  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
834  if (jmg)
835  copyJointGroupVelocities(jmg, values);
836  }
837 
841  void copyJointGroupVelocities(const JointModelGroup* group, Eigen::VectorXd& values) const;
842 
852  void setJointGroupAccelerations(const std::string& joint_group_name, const double* gstate)
853  {
854  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
855  if (jmg)
856  setJointGroupAccelerations(jmg, gstate);
857  }
858 
862  void setJointGroupAccelerations(const std::string& joint_group_name, const std::vector<double>& gstate)
863  {
864  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
865  if (jmg)
866  setJointGroupAccelerations(jmg, &gstate[0]);
867  }
868 
872  void setJointGroupAccelerations(const JointModelGroup* group, const std::vector<double>& gstate)
873  {
874  setJointGroupAccelerations(group, &gstate[0]);
875  }
876 
880  void setJointGroupAccelerations(const JointModelGroup* group, const double* gstate);
881 
885  void setJointGroupAccelerations(const std::string& joint_group_name, const Eigen::VectorXd& values)
886  {
887  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
888  if (jmg)
889  setJointGroupAccelerations(jmg, values);
890  }
891 
895  void setJointGroupAccelerations(const JointModelGroup* group, const Eigen::VectorXd& values);
896 
900  void copyJointGroupAccelerations(const std::string& joint_group_name, std::vector<double>& gstate) const
901  {
902  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
903  if (jmg)
904  {
905  gstate.resize(jmg->getVariableCount());
906  copyJointGroupAccelerations(jmg, &gstate[0]);
907  }
908  }
909 
913  void copyJointGroupAccelerations(const std::string& joint_group_name, double* gstate) const
914  {
915  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
916  if (jmg)
917  copyJointGroupAccelerations(jmg, gstate);
918  }
919 
923  void copyJointGroupAccelerations(const JointModelGroup* group, std::vector<double>& gstate) const
924  {
925  gstate.resize(group->getVariableCount());
926  copyJointGroupAccelerations(group, &gstate[0]);
927  }
928 
932  void copyJointGroupAccelerations(const JointModelGroup* group, double* gstate) const;
933 
937  void copyJointGroupAccelerations(const std::string& joint_group_name, Eigen::VectorXd& values) const
938  {
939  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
940  if (jmg)
941  copyJointGroupAccelerations(jmg, values);
942  }
943 
947  void copyJointGroupAccelerations(const JointModelGroup* group, Eigen::VectorXd& values) const;
948 
961  bool setToIKSolverFrame(Eigen::Isometry3d& pose, const kinematics::KinematicsBaseConstPtr& solver);
962 
969  bool setToIKSolverFrame(Eigen::Isometry3d& pose, const std::string& ik_frame);
970 
977  bool setFromIK(const JointModelGroup* group, const geometry_msgs::Pose& pose, double timeout = 0.0,
980  [[deprecated("The attempts argument is not supported anymore.")]] bool
981  setFromIK(const JointModelGroup* group, const geometry_msgs::Pose& pose, unsigned int /*attempts*/,
982  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
984  {
985  return setFromIK(group, pose, timeout, constraint, options);
986  }
987 
995  bool setFromIK(const JointModelGroup* group, const geometry_msgs::Pose& pose, const std::string& tip,
996  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
998  [[deprecated("The attempts argument is not supported anymore.")]] bool
999  setFromIK(const JointModelGroup* group, const geometry_msgs::Pose& pose, const std::string& tip,
1000  unsigned int /*attempts*/, double timeout = 0.0,
1003  {
1004  return setFromIK(group, pose, tip, timeout, constraint, options);
1005  }
1006 
1013  bool setFromIK(const JointModelGroup* group, const Eigen::Isometry3d& pose, double timeout = 0.0,
1016  [[deprecated("The attempts argument is not supported anymore.")]] bool
1017  setFromIK(const JointModelGroup* group, const Eigen::Isometry3d& pose, unsigned int /*attempts*/,
1018  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
1020  {
1021  return setFromIK(group, pose, timeout, constraint, options);
1022  }
1023 
1030  bool setFromIK(const JointModelGroup* group, const Eigen::Isometry3d& pose, const std::string& tip,
1031  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
1033  [[deprecated("The attempts argument is not supported anymore.")]] bool
1034  setFromIK(const JointModelGroup* group, const Eigen::Isometry3d& pose, const std::string& tip,
1035  unsigned int /*attempts*/, double timeout = 0.0,
1038  {
1039  return setFromIK(group, pose, tip, timeout, constraint, options);
1040  }
1041 
1050  bool setFromIK(const JointModelGroup* group, const Eigen::Isometry3d& pose, const std::string& tip,
1051  const std::vector<double>& consistency_limits, double timeout = 0.0,
1054  [[deprecated("The attempts argument is not supported anymore.")]] bool
1055  setFromIK(const JointModelGroup* group, const Eigen::Isometry3d& pose, const std::string& tip,
1056  const std::vector<double>& consistency_limits, unsigned int /*attempts*/, double timeout = 0.0,
1059  {
1060  return setFromIK(group, pose, tip, consistency_limits, timeout, constraint, options);
1061  }
1062 
1072  bool setFromIK(const JointModelGroup* group, const EigenSTL::vector_Isometry3d& poses,
1073  const std::vector<std::string>& tips, double timeout = 0.0,
1076  [[deprecated("The attempts argument is not supported anymore.")]] bool
1078  const std::vector<std::string>& tips, unsigned int /*attempts*/, double timeout = 0.0,
1081  {
1082  return setFromIK(group, poses, tips, timeout, constraint, options);
1083  }
1084 
1095  bool setFromIK(const JointModelGroup* group, const EigenSTL::vector_Isometry3d& poses,
1096  const std::vector<std::string>& tips, const std::vector<std::vector<double> >& consistency_limits,
1097  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
1099  [[deprecated("The attempts argument is not supported anymore.")]] bool
1101  const std::vector<std::string>& tips, const std::vector<std::vector<double> >& consistency_limits,
1102  unsigned int /*attempts*/, double timeout = 0.0,
1105  {
1106  return setFromIK(group, poses, tips, consistency_limits, timeout, constraint, options);
1107  }
1108 
1117  bool setFromIKSubgroups(const JointModelGroup* group, const EigenSTL::vector_Isometry3d& poses,
1118  const std::vector<std::string>& tips,
1119  const std::vector<std::vector<double> >& consistency_limits, double timeout = 0.0,
1122  [[deprecated("The attempts argument is not supported anymore.")]] bool
1124  const std::vector<std::string>& tips, const std::vector<std::vector<double> >& consistency_limits,
1125  unsigned int /*attempts*/, double timeout = 0.0,
1128  {
1129  return setFromIKSubgroups(group, poses, tips, consistency_limits, timeout, constraint, options);
1130  }
1131 
1139  bool setFromDiffIK(const JointModelGroup* group, const Eigen::VectorXd& twist, const std::string& tip, double dt,
1141 
1149  bool setFromDiffIK(const JointModelGroup* group, const geometry_msgs::Twist& twist, const std::string& tip, double dt,
1151 
1182  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1183  const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
1184  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
1187 
1188  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1189  const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
1190  double max_step, double jump_threshold_factor,
1193  {
1194  return computeCartesianPath(group, traj, link, direction, global_reference_frame, distance,
1195  MaxEEFStep(max_step, max_step), JumpThreshold(jump_threshold_factor), validCallback,
1196  options);
1197  }
1198 
1205  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1206  const Eigen::Isometry3d& target, bool global_reference_frame, const MaxEEFStep& max_step,
1207  const JumpThreshold& jump_threshold,
1210 
1211  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1212  const Eigen::Isometry3d& target, bool global_reference_frame, double max_step,
1213  double jump_threshold_factor,
1216  {
1217  return computeCartesianPath(group, traj, link, target, global_reference_frame, MaxEEFStep(max_step),
1218  JumpThreshold(jump_threshold_factor), validCallback, options);
1219  }
1220 
1227  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1228  const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame,
1229  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
1232 
1233  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1234  const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame,
1235  double max_step, double jump_threshold_factor,
1238  {
1239  return computeCartesianPath(group, traj, link, waypoints, global_reference_frame, MaxEEFStep(max_step),
1240  JumpThreshold(jump_threshold_factor), validCallback, options);
1241  }
1242 
1258  static double testJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1259  const JumpThreshold& jump_threshold);
1260 
1271  static double testRelativeJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1272  double jump_threshold_factor);
1273 
1286  static double testAbsoluteJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1287  double revolute_jump_threshold, double prismatic_jump_threshold);
1288 
1298  bool getJacobian(const JointModelGroup* group, const LinkModel* link, const Eigen::Vector3d& reference_point_position,
1299  Eigen::MatrixXd& jacobian, bool use_quaternion_representation = false) const;
1300 
1310  bool getJacobian(const JointModelGroup* group, const LinkModel* link, const Eigen::Vector3d& reference_point_position,
1311  Eigen::MatrixXd& jacobian, bool use_quaternion_representation = false)
1312  {
1313  updateLinkTransforms();
1314  return static_cast<const RobotState*>(this)->getJacobian(group, link, reference_point_position, jacobian,
1315  use_quaternion_representation);
1316  }
1317 
1324  Eigen::MatrixXd getJacobian(const JointModelGroup* group,
1325  const Eigen::Vector3d& reference_point_position = Eigen::Vector3d(0.0, 0.0, 0.0)) const;
1326 
1333  Eigen::MatrixXd getJacobian(const JointModelGroup* group,
1334  const Eigen::Vector3d& reference_point_position = Eigen::Vector3d(0.0, 0.0, 0.0))
1335  {
1336  updateLinkTransforms();
1337  return static_cast<const RobotState*>(this)->getJacobian(group, reference_point_position);
1338  }
1339 
1342  void computeVariableVelocity(const JointModelGroup* jmg, Eigen::VectorXd& qdot, const Eigen::VectorXd& twist,
1343  const LinkModel* tip) const;
1344 
1347  void computeVariableVelocity(const JointModelGroup* jmg, Eigen::VectorXd& qdot, const Eigen::VectorXd& twist,
1348  const LinkModel* tip)
1349  {
1350  updateLinkTransforms();
1351  static_cast<const RobotState*>(this)->computeVariableVelocity(jmg, qdot, twist, tip);
1352  }
1353 
1357  bool integrateVariableVelocity(const JointModelGroup* jmg, const Eigen::VectorXd& qdot, double dt,
1359 
1366  void setVariableValues(const sensor_msgs::JointState& msg)
1367  {
1368  if (!msg.position.empty())
1369  setVariablePositions(msg.name, msg.position);
1370  if (!msg.velocity.empty())
1371  setVariableVelocities(msg.name, msg.velocity);
1372  }
1373 
1377  void setToDefaultValues();
1378 
1380  bool setToDefaultValues(const JointModelGroup* group, const std::string& name);
1381 
1383  void setToRandomPositions();
1384 
1386  void setToRandomPositions(const JointModelGroup* group);
1387 
1390  void setToRandomPositions(const JointModelGroup* group, random_numbers::RandomNumberGenerator& rng);
1391 
1397  void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& near, double distance);
1398 
1406  void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& near,
1407  const std::vector<double>& distances);
1408 
1417  void updateCollisionBodyTransforms();
1418 
1421  void updateLinkTransforms();
1422 
1424  void update(bool force = false);
1425 
1434  void updateStateWithLinkAt(const std::string& link_name, const Eigen::Isometry3d& transform, bool backward = false)
1435  {
1436  updateStateWithLinkAt(robot_model_->getLinkModel(link_name), transform, backward);
1437  }
1438 
1440  void updateStateWithLinkAt(const LinkModel* link, const Eigen::Isometry3d& transform, bool backward = false);
1441 
1442  const Eigen::Isometry3d& getGlobalLinkTransform(const std::string& link_name)
1443  {
1444  return getGlobalLinkTransform(robot_model_->getLinkModel(link_name));
1445  }
1446 
1447  const Eigen::Isometry3d& getGlobalLinkTransform(const LinkModel* link)
1448  {
1449  updateLinkTransforms();
1450  return global_link_transforms_[link->getLinkIndex()];
1451  }
1452 
1453  const Eigen::Isometry3d& getCollisionBodyTransform(const std::string& link_name, std::size_t index)
1454  {
1455  return getCollisionBodyTransform(robot_model_->getLinkModel(link_name), index);
1456  }
1457 
1458  const Eigen::Isometry3d& getCollisionBodyTransform(const LinkModel* link, std::size_t index)
1459  {
1460  updateCollisionBodyTransforms();
1461  return global_collision_body_transforms_[link->getFirstCollisionBodyTransformIndex() + index];
1462  }
1463 
1464  const Eigen::Isometry3d& getJointTransform(const std::string& joint_name)
1465  {
1466  return getJointTransform(robot_model_->getJointModel(joint_name));
1467  }
1468 
1469  const Eigen::Isometry3d& getJointTransform(const JointModel* joint)
1470  {
1471  const int idx = joint->getJointIndex();
1472  unsigned char& dirty = dirty_joint_transforms_[idx];
1473  if (dirty)
1474  {
1475  joint->computeTransform(position_ + joint->getFirstVariableIndex(), variable_joint_transforms_[idx]);
1476  dirty = 0;
1477  }
1478  return variable_joint_transforms_[idx];
1479  }
1480 
1481  const Eigen::Isometry3d& getGlobalLinkTransform(const std::string& link_name) const
1482  {
1483  return getGlobalLinkTransform(robot_model_->getLinkModel(link_name));
1484  }
1485 
1486  const Eigen::Isometry3d& getGlobalLinkTransform(const LinkModel* link) const
1487  {
1488  BOOST_VERIFY(checkLinkTransforms());
1489  return global_link_transforms_[link->getLinkIndex()];
1490  }
1491 
1492  const Eigen::Isometry3d& getCollisionBodyTransform(const std::string& link_name, std::size_t index) const
1493  {
1494  return getCollisionBodyTransform(robot_model_->getLinkModel(link_name), index);
1495  }
1496 
1497  const Eigen::Isometry3d& getCollisionBodyTransform(const LinkModel* link, std::size_t index) const
1498  {
1499  BOOST_VERIFY(checkCollisionTransforms());
1500  return global_collision_body_transforms_[link->getFirstCollisionBodyTransformIndex() + index];
1501  }
1502 
1503  const Eigen::Isometry3d& getJointTransform(const std::string& joint_name) const
1504  {
1505  return getJointTransform(robot_model_->getJointModel(joint_name));
1506  }
1507 
1508  const Eigen::Isometry3d& getJointTransform(const JointModel* joint) const
1509  {
1510  BOOST_VERIFY(checkJointTransforms(joint));
1511  return variable_joint_transforms_[joint->getJointIndex()];
1512  }
1513 
1514  bool dirtyJointTransform(const JointModel* joint) const
1515  {
1516  return dirty_joint_transforms_[joint->getJointIndex()];
1517  }
1518 
1519  bool dirtyLinkTransforms() const
1520  {
1521  return dirty_link_transforms_;
1522  }
1523 
1525  {
1526  return dirty_link_transforms_ || dirty_collision_body_transforms_;
1527  }
1528 
1530  bool dirty() const
1531  {
1532  return dirtyCollisionBodyTransforms();
1533  }
1534 
1541  double distance(const RobotState& other) const
1542  {
1543  return robot_model_->distance(position_, other.getVariablePositions());
1544  }
1545 
1546  double distance(const RobotState& other, const JointModelGroup* joint_group) const;
1547 
1548  double distance(const RobotState& other, const JointModel* joint) const
1549  {
1550  const int idx = joint->getFirstVariableIndex();
1551  return joint->distance(position_ + idx, other.position_ + idx);
1552  }
1553 
1557  void interpolate(const RobotState& to, double t, RobotState& state) const;
1558 
1562  void interpolate(const RobotState& to, double t, RobotState& state, const JointModelGroup* joint_group) const;
1563 
1567  void interpolate(const RobotState& to, double t, RobotState& state, const JointModel* joint) const
1568  {
1569  const int idx = joint->getFirstVariableIndex();
1570  joint->interpolate(position_ + idx, to.position_ + idx, t, state.position_ + idx);
1571  state.markDirtyJointTransforms(joint);
1572  state.updateMimicJoint(joint);
1573  }
1574 
1575  void enforceBounds();
1576  void enforceBounds(const JointModelGroup* joint_group);
1577  void enforceBounds(const JointModel* joint)
1578  {
1579  enforcePositionBounds(joint);
1580  if (has_velocity_)
1581  enforceVelocityBounds(joint);
1582  }
1584  {
1585  if (joint->enforcePositionBounds(position_ + joint->getFirstVariableIndex()))
1586  {
1587  markDirtyJointTransforms(joint);
1588  updateMimicJoint(joint);
1589  }
1590  }
1591 
1593  void harmonizePositions();
1594  void harmonizePositions(const JointModelGroup* joint_group);
1595  void harmonizePosition(const JointModel* joint)
1596  {
1597  if (joint->harmonizePosition(position_ + joint->getFirstVariableIndex()))
1598  // no need to mark transforms dirty, as the transform hasn't changed
1599  updateMimicJoint(joint);
1600  }
1601 
1603  {
1604  joint->enforceVelocityBounds(velocity_ + joint->getFirstVariableIndex());
1605  }
1606 
1607  bool satisfiesBounds(double margin = 0.0) const;
1608  bool satisfiesBounds(const JointModelGroup* joint_group, double margin = 0.0) const;
1609  bool satisfiesBounds(const JointModel* joint, double margin = 0.0) const
1610  {
1611  return satisfiesPositionBounds(joint, margin) && (!has_velocity_ || satisfiesVelocityBounds(joint, margin));
1612  }
1613  bool satisfiesPositionBounds(const JointModel* joint, double margin = 0.0) const
1614  {
1615  return joint->satisfiesPositionBounds(getJointPositions(joint), margin);
1616  }
1617  bool satisfiesVelocityBounds(const JointModel* joint, double margin = 0.0) const
1618  {
1619  return joint->satisfiesVelocityBounds(getJointVelocities(joint), margin);
1620  }
1621 
1624  std::pair<double, const JointModel*> getMinDistanceToPositionBounds() const;
1625 
1628  std::pair<double, const JointModel*> getMinDistanceToPositionBounds(const JointModelGroup* group) const;
1629 
1632  std::pair<double, const JointModel*>
1633  getMinDistanceToPositionBounds(const std::vector<const JointModel*>& joints) const;
1634 
1641  bool isValidVelocityMove(const RobotState& other, const JointModelGroup* group, double dt) const;
1642 
1668  void attachBody(AttachedBody* attached_body);
1669 
1684  void attachBody(const std::string& id, const std::vector<shapes::ShapeConstPtr>& shapes,
1685  const EigenSTL::vector_Isometry3d& attach_trans, const std::set<std::string>& touch_links,
1686  const std::string& link_name,
1687  const trajectory_msgs::JointTrajectory& detach_posture = trajectory_msgs::JointTrajectory());
1688 
1703  void attachBody(const std::string& id, const std::vector<shapes::ShapeConstPtr>& shapes,
1704  const EigenSTL::vector_Isometry3d& attach_trans, const std::vector<std::string>& touch_links,
1705  const std::string& link_name,
1706  const trajectory_msgs::JointTrajectory& detach_posture = trajectory_msgs::JointTrajectory())
1707  {
1708  std::set<std::string> touch_links_set(touch_links.begin(), touch_links.end());
1709  attachBody(id, shapes, attach_trans, touch_links_set, link_name, detach_posture);
1710  }
1711 
1713  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies) const;
1714 
1716  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const JointModelGroup* lm) const;
1717 
1719  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const LinkModel* lm) const;
1720 
1723  bool clearAttachedBody(const std::string& id);
1724 
1726  void clearAttachedBodies(const LinkModel* link);
1727 
1729  void clearAttachedBodies(const JointModelGroup* group);
1730 
1732  void clearAttachedBodies();
1733 
1735  const AttachedBody* getAttachedBody(const std::string& name) const;
1736 
1738  bool hasAttachedBody(const std::string& id) const;
1739 
1740  void setAttachedBodyUpdateCallback(const AttachedBodyCallback& callback);
1745  void computeAABB(std::vector<double>& aabb) const;
1746 
1749  void computeAABB(std::vector<double>& aabb)
1750  {
1751  updateLinkTransforms();
1752  static_cast<const RobotState*>(this)->computeAABB(aabb);
1753  }
1754 
1757  {
1758  if (!rng_)
1760  return *rng_;
1761  }
1762 
1764  const Eigen::Isometry3d& getFrameTransform(const std::string& frame_id);
1765 
1767  const Eigen::Isometry3d& getFrameTransform(const std::string& frame_id) const;
1768 
1770  bool knowsFrameTransform(const std::string& frame_id) const;
1771 
1779  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1780  const std_msgs::ColorRGBA& color, const std::string& ns, const ros::Duration& dur,
1781  bool include_attached = false) const;
1782 
1790  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1791  const std_msgs::ColorRGBA& color, const std::string& ns, const ros::Duration& dur,
1792  bool include_attached = false)
1793  {
1794  updateCollisionBodyTransforms();
1795  static_cast<const RobotState*>(this)->getRobotMarkers(arr, link_names, color, ns, dur, include_attached);
1796  }
1797 
1802  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1803  bool include_attached = false) const;
1804 
1809  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1810  bool include_attached = false)
1811  {
1812  updateCollisionBodyTransforms();
1813  static_cast<const RobotState*>(this)->getRobotMarkers(arr, link_names, include_attached);
1814  }
1815 
1816  void printStatePositions(std::ostream& out = std::cout) const;
1817 
1819  void printStatePositionsWithJointLimits(const moveit::core::JointModelGroup* jmg,
1820  std::ostream& out = std::cout) const;
1821 
1822  void printStateInfo(std::ostream& out = std::cout) const;
1823 
1824  void printTransforms(std::ostream& out = std::cout) const;
1825 
1826  void printTransform(const Eigen::Isometry3d& transform, std::ostream& out = std::cout) const;
1827 
1828  void printDirtyInfo(std::ostream& out = std::cout) const;
1829 
1830  std::string getStateTreeString(const std::string& prefix = "") const;
1831 
1832 private:
1833  void allocMemory();
1834  void initTransforms();
1835  void copyFrom(const RobotState& other);
1836 
1838  {
1839  dirty_joint_transforms_[joint->getJointIndex()] = 1;
1840  dirty_link_transforms_ =
1841  dirty_link_transforms_ == NULL ? joint : robot_model_->getCommonRoot(dirty_link_transforms_, joint);
1842  }
1843 
1845  {
1846  const std::vector<const JointModel*>& jm = group->getActiveJointModels();
1847  for (std::size_t i = 0; i < jm.size(); ++i)
1848  dirty_joint_transforms_[jm[i]->getJointIndex()] = 1;
1849  dirty_link_transforms_ = dirty_link_transforms_ == NULL ?
1850  group->getCommonRoot() :
1851  robot_model_->getCommonRoot(dirty_link_transforms_, group->getCommonRoot());
1852  }
1853 
1854  void markVelocity();
1855  void markAcceleration();
1856  void markEffort();
1857 
1858  void updateMimicJoint(const JointModel* joint)
1859  {
1860  const std::vector<const JointModel*>& mim = joint->getMimicRequests();
1861  double v = position_[joint->getFirstVariableIndex()];
1862  for (std::size_t i = 0; i < mim.size(); ++i)
1863  {
1864  position_[mim[i]->getFirstVariableIndex()] = mim[i]->getMimicFactor() * v + mim[i]->getMimicOffset();
1865  markDirtyJointTransforms(mim[i]);
1866  }
1867  }
1868 
1870  /* use updateMimicJoints() instead, which also marks joints dirty */
1871  [[deprecated]] void updateMimicJoint(const std::vector<const JointModel*>& mim)
1872  {
1873  for (std::size_t i = 0; i < mim.size(); ++i)
1874  {
1875  const int fvi = mim[i]->getFirstVariableIndex();
1876  position_[fvi] =
1877  mim[i]->getMimicFactor() * position_[mim[i]->getMimic()->getFirstVariableIndex()] + mim[i]->getMimicOffset();
1878  // Only mark joint transform dirty, but not the associated link transform
1879  // as this function is always used in combination of
1880  // updateMimicJoint(group->getMimicJointModels()) + markDirtyJointTransforms(group);
1881  dirty_joint_transforms_[mim[i]->getJointIndex()] = 1;
1882  }
1883  }
1884 
1887  {
1888  for (const JointModel* jm : group->getMimicJointModels())
1889  {
1890  const int fvi = jm->getFirstVariableIndex();
1891  position_[fvi] = jm->getMimicFactor() * position_[jm->getMimic()->getFirstVariableIndex()] + jm->getMimicOffset();
1892  markDirtyJointTransforms(jm);
1893  }
1894  markDirtyJointTransforms(group);
1895  }
1896 
1897  void updateLinkTransformsInternal(const JointModel* start);
1898 
1899  void getMissingKeys(const std::map<std::string, double>& variable_map,
1900  std::vector<std::string>& missing_variables) const;
1901  void getStateTreeJointString(std::ostream& ss, const JointModel* jm, const std::string& pfx0, bool last) const;
1902 
1904  bool checkJointTransforms(const JointModel* joint) const;
1905 
1907  bool checkLinkTransforms() const;
1908 
1910  bool checkCollisionTransforms() const;
1911 
1912  RobotModelConstPtr robot_model_;
1913  void* memory_;
1914 
1915  double* position_;
1916  double* velocity_;
1917  double* acceleration_;
1918  double* effort_;
1922 
1925 
1926  Eigen::Isometry3d* variable_joint_transforms_; // this points to an element in transforms_, so it is aligned
1927  Eigen::Isometry3d* global_link_transforms_; // this points to an element in transforms_, so it is aligned
1928  Eigen::Isometry3d* global_collision_body_transforms_; // this points to an element in transforms_, so it is aligned
1929  unsigned char* dirty_joint_transforms_;
1930 
1932  std::map<std::string, AttachedBody*> attached_body_map_;
1933 
1937 
1944 };
1945 
1947 std::ostream& operator<<(std::ostream& out, const RobotState& s);
1948 }
1949 }
1950 
1951 #endif
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:549
const Eigen::Isometry3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index)
Definition: robot_state.h:1453
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:329
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
Definition: robot_state.h:1756
JumpThreshold(double jt_factor)
Definition: robot_state.h:80
A set of options for the kinematics solver.
Eigen::Isometry3d * variable_joint_transforms_
Definition: robot_state.h:1926
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:1749
void updateMimicJoint(const JointModel *joint)
Definition: robot_state.h:1858
const double * getJointEffort(const JointModel *joint) const
Definition: robot_state.h:626
Core components of MoveIt!
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:817
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:913
void getRobotMarkers(visualization_msgs::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:1809
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:650
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:852
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:240
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:277
ROSCPP_DECL void start()
void harmonizePosition(const JointModel *joint)
Definition: robot_state.h:1595
const double * getJointVelocities(const std::string &joint_name) const
Definition: robot_state.h:601
void attachBody(const std::string &id, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &attach_trans, const std::vector< std::string > &touch_links, const std::string &link_name, const trajectory_msgs::JointTrajectory &detach_posture=trajectory_msgs::JointTrajectory())
Add an attached body to a link.
Definition: robot_state.h:1703
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:90
const std::vector< const JointModel * > & getMimicRequests() const
The joint models whose values would be modified if the value of this joint changed.
Definition: joint_model.h:391
void updateMimicJoints(const JointModelGroup *group)
Update all mimic joints within group.
Definition: robot_state.h:1886
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:461
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
Definition: robot_state.h:262
const double * getJointVelocities(const JointModel *joint) const
Definition: robot_state.h:606
std::vector< double > values
bool dirtyJointTransform(const JointModel *joint) const
Definition: robot_state.h:1514
void enforcePositionBounds(const JointModel *joint)
Definition: robot_state.h:1583
const double * getJointAccelerations(const JointModel *joint) const
Definition: robot_state.h:616
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:831
double computeCartesianPath(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, const LinkModel *link, const EigenSTL::vector_Isometry3d &waypoints, bool global_reference_frame, double max_step, double jump_threshold_factor, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Definition: robot_state.h:1233
int getJointIndex() const
Get the index of this joint within the robot model.
Definition: joint_model.h:214
bool setFromIK(const JointModelGroup *group, const Eigen::Isometry3d &pose, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Definition: robot_state.h:1017
int getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
Definition: link_model.h:87
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:286
const JointModel * dirty_collision_body_transforms_
Definition: robot_state.h:1924
bool setFromIK(const JointModelGroup *group, const geometry_msgs::Pose &pose, const std::string &tip, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Definition: robot_state.h:999
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
Definition: robot_state.h:1464
void enforceVelocityBounds(const JointModel *joint)
Definition: robot_state.h:1602
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:200
virtual bool harmonizePosition(double *values, const Bounds &other_bounds) const
Definition: joint_model.cpp:93
virtual void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const =0
Given the joint values for a joint, compute the corresponding transform.
const Eigen::Isometry3d & getCollisionBodyTransform(const LinkModel *link, std::size_t index)
Definition: robot_state.h:1458
bool setFromIK(const JointModelGroup *group, const Eigen::Isometry3d &pose, const std::string &tip, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Definition: robot_state.h:1034
void setJointPositions(const JointModel *joint, const double *position)
Definition: robot_state.h:564
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:900
Eigen::Isometry3d * global_link_transforms_
Definition: robot_state.h:1927
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:278
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:746
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name) const
Definition: robot_state.h:1481
void interpolate(const RobotState &to, double t, RobotState &state, const JointModel *joint) const
Update state by interpolating form this state towards to, at time t in [0,1] but only for the joint j...
Definition: robot_state.h:1567
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully. If you change these values externally you need to make sure you trigger a forced update for the state by calling update(true).
Definition: robot_state.h:180
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:421
bool setFromIK(const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, const std::vector< std::vector< double > > &consistency_limits, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Definition: robot_state.h:1100
geometry_msgs::TransformStamped t
void markDirtyJointTransforms(const JointModel *joint)
Definition: robot_state.h:1837
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:513
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:660
bool dirtyLinkTransforms() const
Definition: robot_state.h:1519
void setJointPositions(const std::string &joint_name, const std::vector< double > &position)
Definition: robot_state.h:554
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...
const JointModel * getCommonRoot() const
Get the common root of all joint roots; not necessarily part of this group.
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
Definition: robot_state.h:167
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:1333
const Eigen::Isometry3d & getGlobalLinkTransform(const LinkModel *link) const
Definition: robot_state.h:1486
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
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:428
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:794
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 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:506
const double * getJointEffort(const std::string &joint_name) const
Definition: robot_state.h:621
const Eigen::Isometry3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index) const
Definition: robot_state.h:1492
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:756
const double * getJointAccelerations(const std::string &joint_name) const
Definition: robot_state.h:611
bool satisfiesPositionBounds(const JointModel *joint, double margin=0.0) const
Definition: robot_state.h:1613
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:862
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:487
void enforceBounds(const JointModel *joint)
Definition: robot_state.h:1577
const Eigen::Isometry3d & getJointTransform(const JointModel *joint)
Definition: robot_state.h:1469
const Eigen::Isometry3d & getCollisionBodyTransform(const LinkModel *link, std::size_t index) const
Definition: robot_state.h:1497
bool setFromIK(const JointModelGroup *group, const geometry_msgs::Pose &pose, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Definition: robot_state.h:981
Struct for containing jump_threshold.
Definition: robot_state.h:70
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) ...
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:725
MOVEIT_CLASS_FORWARD(RobotModel)
MaxEEFStep(double translation=0.0, double rotation=0.0)
Definition: robot_state.h:97
void setJointPositions(const JointModel *joint, const std::vector< double > &position)
Definition: robot_state.h:559
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:807
boost::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
Definition: attached_body.h:50
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:309
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:392
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:779
bool hasAccelerations() const
By default, if accelerations are never set or initialized, the state remembers that there are no acce...
Definition: robot_state.h:355
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:1310
options
bool enforcePositionBounds(double *values) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous joints are made between -Pi and Pi. Returns true if changes were made.
Definition: joint_model.h:290
const std::vector< const JointModel * > & getMimicJointModels() const
Get the mimic joints that are part of this group.
unsigned char * dirty_joint_transforms_
Definition: robot_state.h:1929
virtual void computeVariablePositions(const Eigen::Isometry3d &transform, double *joint_values) const =0
Given the transform generated by joint, compute the corresponding joint values.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Definition: joint_model.h:196
bool dirty() const
Returns true if anything in this state is dirty.
Definition: robot_state.h:1530
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name) const
Definition: robot_state.h:1503
AttachedBodyCallback attached_body_update_callback_
This event is called when there is a change in the attached bodies for this state; The event specifie...
Definition: robot_state.h:1936
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:885
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
Definition: robot_state.h:137
Struct for containing max_step for computeCartesianPath.
Definition: robot_state.h:95
double computeCartesianPath(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, const LinkModel *link, const Eigen::Isometry3d &target, bool global_reference_frame, double max_step, double jump_threshold_factor, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Definition: robot_state.h:1211
double getVariableVelocity(int index) const
Get the velocity of a particular variable. The variable is specified by its index. No checks are performed for the validity of the index passed.
Definition: robot_state.h:337
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:469
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:673
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
Definition: joint_model.h:108
void getRobotMarkers(visualization_msgs::MarkerArray &arr, const std::vector< std::string > &link_names, const std_msgs::ColorRGBA &color, const std::string &ns, const ros::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:1790
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:701
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:1434
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints...
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:688
bool setFromIKSubgroups(const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, const std::vector< std::vector< double > > &consistency_limits, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Definition: robot_state.h:1123
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
Definition: joint_model.h:318
void markDirtyJointTransforms(const JointModelGroup *group)
Definition: robot_state.h:1844
int getFirstCollisionBodyTransformIndex() const
Definition: link_model.h:97
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:269
bool dirtyCollisionBodyTransforms() const
Definition: robot_state.h:1524
void setJointPositions(const std::string &joint_name, const Eigen::Isometry3d &transform)
Definition: robot_state.h:571
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:937
bool setFromIK(const JointModelGroup *group, const Eigen::Isometry3d &pose, const std::string &tip, const std::vector< double > &consistency_limits, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Definition: robot_state.h:1055
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:322
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
Definition: robot_state.h:155
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:1347
JumpThreshold(double jt_revolute, double jt_prismatic)
Definition: robot_state.h:85
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:520
const JointModel * dirty_link_transforms_
Definition: robot_state.h:1923
std::size_t getVariableCount() const
Get the number of variables that make up this state.
Definition: robot_state.h:143
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:363
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:923
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Definition: robot_state.h:1442
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:640
random_numbers::RandomNumberGenerator * rng_
For certain operations a state needs a random number generator. However, it may be slightly expensive...
Definition: robot_state.h:1943
const double * getVariablePositions() const
Get a raw pointer to the positions of the variables stored in this state.
Definition: robot_state.h:187
RobotModelConstPtr robot_model_
Definition: robot_state.h:1912
void setVariableValues(const sensor_msgs::JointState &msg)
Definition: robot_state.h:1366
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:381
Eigen::Isometry3d * global_collision_body_transforms_
Definition: robot_state.h:1928
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:528
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:122
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:414
bool satisfiesVelocityBounds(const JointModel *joint, double margin=0.0) const
Definition: robot_state.h:1617
A link from the robot. Contains the constant transform applied to the link and its geometry...
Definition: link_model.h:72
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
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:478
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:453
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
bool satisfiesBounds(const JointModel *joint, double margin=0.0) const
Definition: robot_state.h:1609
int getFirstVariableIndex() const
Get the index of this joint&#39;s first variable within the full robot state.
Definition: joint_model.h:202
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:872
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:221
Main namespace for MoveIt!
double distance(const RobotState &other, const JointModel *joint) const
Definition: robot_state.h:1548
double getVariablePosition(int index) const
Get the position of a particular variable. The variable is specified by its index. No checks are performed for the validity of the index passed.
Definition: robot_state.h:248
double getVariableAcceleration(int index) const
Get the acceleration of a particular variable. The variable is specified by its index. No checks are performed for the validity of the index passed.
Definition: robot_state.h:436
const JointModel * getJointModel(const std::string &joint) const
Get the model of a particular joint.
Definition: robot_state.h:161
const Eigen::Isometry3d & getJointTransform(const JointModel *joint) const
Definition: robot_state.h:1508
Object defining bodies that can be attached to robot links. This is useful when handling objects pick...
Definition: attached_body.h:56
bool setFromIK(const JointModelGroup *group, const EigenSTL::vector_Isometry3d &poses, const std::vector< std::string > &tips, unsigned int, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Definition: robot_state.h:1077
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
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:149
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:228
double distance(const RobotState &other) const
Definition: robot_state.h:1541
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:294
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:315
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
boost::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:63
void setJointPositions(const JointModel *joint, const Eigen::Isometry3d &transform)
Definition: robot_state.h:576
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:711
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())
Definition: robot_state.h:1188
const double * getJointPositions(const std::string &joint_name) const
Definition: robot_state.h:591
std::map< std::string, AttachedBody * > attached_body_map_
All attached bodies that are part of this state, indexed by their name.
Definition: robot_state.h:1932
const double * getJointPositions(const JointModel *joint) const
Definition: robot_state.h:596
const Eigen::Isometry3d & getGlobalLinkTransform(const LinkModel *link)
Definition: robot_state.h:1447
const double * getVariableAccelerations() const
Get const raw access to the accelerations of the variables that make up this state. The values are in the same order as reported by getVariableNames()
Definition: robot_state.h:371
void setJointVelocities(const JointModel *joint, const double *velocity)
Definition: robot_state.h:583
void updateMimicJoint(const std::vector< const JointModel *> &mim)
Update a set of joints that are certain to be mimicking other joints.
Definition: robot_state.h:1871


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sat Jul 11 2020 03:51:21