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 
44 #include <sensor_msgs/JointState.h>
45 #include <visualization_msgs/MarkerArray.h>
46 #include <std_msgs/ColorRGBA.h>
47 #include <geometry_msgs/Twist.h>
48 #include <cassert>
49 
50 #include <boost/assert.hpp>
51 
52 namespace moveit
53 {
54 namespace core
55 {
56 MOVEIT_CLASS_FORWARD(RobotState);
57 
62 typedef boost::function<bool(RobotState* robot_state, const JointModelGroup* joint_group,
63  const double* joint_group_variable_values)>
65 
72 {
73  double factor;
74  double revolute; // Radians
75  double prismatic; // Meters
76 
77  explicit JumpThreshold() : factor(0.0), revolute(0.0), prismatic(0.0)
78  {
79  }
80 
81  explicit JumpThreshold(double jt_factor) : JumpThreshold()
82  {
83  factor = jt_factor;
84  }
85 
86  explicit JumpThreshold(double jt_revolute, double jt_prismatic) : JumpThreshold()
87  {
88  revolute = jt_revolute; // Radians
89  prismatic = jt_prismatic; // Meters
90  }
91 };
92 
96 struct MaxEEFStep
97 {
98  MaxEEFStep(double translation = 0.0, double rotation = 0.0) : translation(translation), rotation(rotation)
99  {
100  }
101 
102  double translation; // Meters
103  double rotation; // Radians
104 };
105 
124 {
125 public:
128  RobotState(const RobotModelConstPtr& robot_model);
129  ~RobotState();
130 
132  RobotState(const RobotState& other);
133 
135  RobotState& operator=(const RobotState& other);
136 
138  const RobotModelConstPtr& getRobotModel() const
139  {
140  return robot_model_;
141  }
142 
144  std::size_t getVariableCount() const
145  {
146  return robot_model_->getVariableCount();
147  }
148 
150  const std::vector<std::string>& getVariableNames() const
151  {
152  return robot_model_->getVariableNames();
153  }
154 
156  const LinkModel* getLinkModel(const std::string& link) const
157  {
158  return robot_model_->getLinkModel(link);
159  }
160 
162  const JointModel* getJointModel(const std::string& joint) const
163  {
164  return robot_model_->getJointModel(joint);
165  }
166 
168  const JointModelGroup* getJointModelGroup(const std::string& group) const
169  {
170  return robot_model_->getJointModelGroup(group);
171  }
172 
182  {
183  return position_;
184  }
185 
188  const double* getVariablePositions() const
189  {
190  return position_;
191  }
192 
196  void setVariablePositions(const double* position);
197 
201  void setVariablePositions(const std::vector<double>& position)
202  {
203  assert(robot_model_->getVariableCount() <= position.size()); // checked only in debug mode
204  setVariablePositions(&position[0]);
205  }
206 
209  void setVariablePositions(const std::map<std::string, double>& variable_map);
210 
213  void setVariablePositions(const std::map<std::string, double>& variable_map,
214  std::vector<std::string>& missing_variables);
215 
218  void setVariablePositions(const std::vector<std::string>& variable_names,
219  const std::vector<double>& variable_position);
220 
222  void setVariablePosition(const std::string& variable, double value)
223  {
224  setVariablePosition(robot_model_->getVariableIndex(variable), value);
225  }
226 
229  void setVariablePosition(int index, double value)
230  {
231  position_[index] = value;
232  const JointModel* jm = robot_model_->getJointOfVariable(index);
233  if (jm)
234  {
235  markDirtyJointTransforms(jm);
236  updateMimicJoint(jm);
237  }
238  }
239 
241  double getVariablePosition(const std::string& variable) const
242  {
243  return position_[robot_model_->getVariableIndex(variable)];
244  }
245 
249  double getVariablePosition(int index) const
250  {
251  return position_[index];
252  }
253 
263  bool hasVelocities() const
264  {
265  return has_velocity_;
266  }
267 
271  {
272  markVelocity();
273  return velocity_;
274  }
275 
278  const double* getVariableVelocities() const
279  {
280  return velocity_;
281  }
282 
284  void setVariableVelocities(const double* velocity)
285  {
286  has_velocity_ = true;
287  // assume everything is in order in terms of array lengths (for efficiency reasons)
288  memcpy(velocity_, velocity, robot_model_->getVariableCount() * sizeof(double));
289  }
290 
292  void setVariableVelocities(const std::vector<double>& velocity)
293  {
294  assert(robot_model_->getVariableCount() <= velocity.size()); // checked only in debug mode
295  setVariableVelocities(&velocity[0]);
296  }
297 
300  void setVariableVelocities(const std::map<std::string, double>& variable_map);
301 
304  void setVariableVelocities(const std::map<std::string, double>& variable_map,
305  std::vector<std::string>& missing_variables);
306 
309  void setVariableVelocities(const std::vector<std::string>& variable_names,
310  const std::vector<double>& variable_velocity);
311 
313  void setVariableVelocity(const std::string& variable, double value)
314  {
315  setVariableVelocity(robot_model_->getVariableIndex(variable), value);
316  }
317 
320  void setVariableVelocity(int index, double value)
321  {
322  markVelocity();
323  velocity_[index] = value;
324  }
325 
327  double getVariableVelocity(const std::string& variable) const
328  {
329  return velocity_[robot_model_->getVariableIndex(variable)];
330  }
331 
335  double getVariableVelocity(int index) const
336  {
337  return velocity_[index];
338  }
339 
350  bool hasAccelerations() const
351  {
352  return has_acceleration_;
353  }
354 
359  {
360  markAcceleration();
361  return acceleration_;
362  }
363 
366  const double* getVariableAccelerations() const
367  {
368  return acceleration_;
369  }
370 
373  void setVariableAccelerations(const double* acceleration)
374  {
375  has_acceleration_ = true;
376  has_effort_ = false;
377 
378  // assume everything is in order in terms of array lengths (for efficiency reasons)
379  memcpy(acceleration_, acceleration, robot_model_->getVariableCount() * sizeof(double));
380  }
381 
384  void setVariableAccelerations(const std::vector<double>& acceleration)
385  {
386  assert(robot_model_->getVariableCount() <= acceleration.size()); // checked only in debug mode
387  setVariableAccelerations(&acceleration[0]);
388  }
389 
392  void setVariableAccelerations(const std::map<std::string, double>& variable_map);
393 
397  void setVariableAccelerations(const std::map<std::string, double>& variable_map,
398  std::vector<std::string>& missing_variables);
399 
402  void setVariableAccelerations(const std::vector<std::string>& variable_names,
403  const std::vector<double>& variable_acceleration);
404 
406  void setVariableAcceleration(const std::string& variable, double value)
407  {
408  setVariableAcceleration(robot_model_->getVariableIndex(variable), value);
409  }
410 
413  void setVariableAcceleration(int index, double value)
414  {
415  markAcceleration();
416  acceleration_[index] = value;
417  }
418 
420  double getVariableAcceleration(const std::string& variable) const
421  {
422  return acceleration_[robot_model_->getVariableIndex(variable)];
423  }
424 
428  double getVariableAcceleration(int index) const
429  {
430  return acceleration_[index];
431  }
432 
442  bool hasEffort() const
443  {
444  return has_effort_;
445  }
446 
451  {
452  markEffort();
453  return effort_;
454  }
455 
458  const double* getVariableEffort() const
459  {
460  return effort_;
461  }
462 
464  void setVariableEffort(const double* effort)
465  {
466  has_effort_ = true;
467  has_acceleration_ = false;
468  // assume everything is in order in terms of array lengths (for efficiency reasons)
469  memcpy(effort_, effort, robot_model_->getVariableCount() * sizeof(double));
470  }
471 
473  void setVariableEffort(const std::vector<double>& effort)
474  {
475  assert(robot_model_->getVariableCount() <= effort.size()); // checked only in debug mode
476  setVariableEffort(&effort[0]);
477  }
478 
480  void setVariableEffort(const std::map<std::string, double>& variable_map);
481 
484  void setVariableEffort(const std::map<std::string, double>& variable_map,
485  std::vector<std::string>& missing_variables);
486 
488  void setVariableEffort(const std::vector<std::string>& variable_names,
489  const std::vector<double>& variable_acceleration);
490 
492  void setVariableEffort(const std::string& variable, double value)
493  {
494  setVariableEffort(robot_model_->getVariableIndex(variable), value);
495  }
496 
499  void setVariableEffort(int index, double value)
500  {
501  markEffort();
502  effort_[index] = value;
503  }
504 
506  double getVariableEffort(const std::string& variable) const
507  {
508  return effort_[robot_model_->getVariableIndex(variable)];
509  }
510 
514  double getVariableEffort(int index) const
515  {
516  return effort_[index];
517  }
518 
524  void setJointPositions(const std::string& joint_name, const double* position)
525  {
526  setJointPositions(robot_model_->getJointModel(joint_name), position);
527  }
528 
529  void setJointPositions(const std::string& joint_name, const std::vector<double>& position)
530  {
531  setJointPositions(robot_model_->getJointModel(joint_name), &position[0]);
532  }
533 
534  void setJointPositions(const JointModel* joint, const std::vector<double>& position)
535  {
536  setJointPositions(joint, &position[0]);
537  }
538 
539  void setJointPositions(const JointModel* joint, const double* position)
540  {
541  memcpy(position_ + joint->getFirstVariableIndex(), position, joint->getVariableCount() * sizeof(double));
542  markDirtyJointTransforms(joint);
543  updateMimicJoint(joint);
544  }
545 
546  void setJointPositions(const std::string& joint_name, const Eigen::Affine3d& transform)
547  {
548  setJointPositions(robot_model_->getJointModel(joint_name), transform);
549  }
550 
551  void setJointPositions(const JointModel* joint, const Eigen::Affine3d& transform)
552  {
553  joint->computeVariablePositions(transform, position_ + joint->getFirstVariableIndex());
554  markDirtyJointTransforms(joint);
555  updateMimicJoint(joint);
556  }
557 
558  void setJointVelocities(const JointModel* joint, const double* velocity)
559  {
560  has_velocity_ = true;
561  memcpy(velocity_ + joint->getFirstVariableIndex(), velocity, joint->getVariableCount() * sizeof(double));
562  }
563 
564  void setJointEfforts(const JointModel* joint, const double* effort);
565 
566  const double* getJointPositions(const std::string& joint_name) const
567  {
568  return getJointPositions(robot_model_->getJointModel(joint_name));
569  }
570 
571  const double* getJointPositions(const JointModel* joint) const
572  {
573  return position_ + joint->getFirstVariableIndex();
574  }
575 
576  const double* getJointVelocities(const std::string& joint_name) const
577  {
578  return getJointVelocities(robot_model_->getJointModel(joint_name));
579  }
580 
581  const double* getJointVelocities(const JointModel* joint) const
582  {
583  return velocity_ + joint->getFirstVariableIndex();
584  }
585 
586  const double* getJointAccelerations(const std::string& joint_name) const
587  {
588  return getJointAccelerations(robot_model_->getJointModel(joint_name));
589  }
590 
591  const double* getJointAccelerations(const JointModel* joint) const
592  {
593  return acceleration_ + joint->getFirstVariableIndex();
594  }
595 
596  const double* getJointEffort(const std::string& joint_name) const
597  {
598  return getJointEffort(robot_model_->getJointModel(joint_name));
599  }
600 
601  const double* getJointEffort(const JointModel* joint) const
602  {
603  return effort_ + joint->getFirstVariableIndex();
604  }
605 
615  void setJointGroupPositions(const std::string& joint_group_name, const double* gstate)
616  {
617  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
618  if (jmg)
619  setJointGroupPositions(jmg, gstate);
620  }
621 
625  void setJointGroupPositions(const std::string& joint_group_name, const std::vector<double>& gstate)
626  {
627  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
628  if (jmg)
629  setJointGroupPositions(jmg, &gstate[0]);
630  }
631 
635  void setJointGroupPositions(const JointModelGroup* group, const std::vector<double>& gstate)
636  {
637  setJointGroupPositions(group, &gstate[0]);
638  }
639 
643  void setJointGroupPositions(const JointModelGroup* group, const double* gstate);
644 
648  void setJointGroupPositions(const std::string& joint_group_name, const Eigen::VectorXd& values)
649  {
650  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
651  if (jmg)
652  setJointGroupPositions(jmg, values);
653  }
654 
658  void setJointGroupPositions(const JointModelGroup* group, const Eigen::VectorXd& values);
659 
663  void copyJointGroupPositions(const std::string& joint_group_name, std::vector<double>& gstate) const
664  {
665  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
666  if (jmg)
667  {
668  gstate.resize(jmg->getVariableCount());
669  copyJointGroupPositions(jmg, &gstate[0]);
670  }
671  }
672 
676  void copyJointGroupPositions(const std::string& joint_group_name, double* gstate) const
677  {
678  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
679  if (jmg)
680  copyJointGroupPositions(jmg, gstate);
681  }
682 
686  void copyJointGroupPositions(const JointModelGroup* group, std::vector<double>& gstate) const
687  {
688  gstate.resize(group->getVariableCount());
689  copyJointGroupPositions(group, &gstate[0]);
690  }
691 
695  void copyJointGroupPositions(const JointModelGroup* group, double* gstate) const;
696 
700  void copyJointGroupPositions(const std::string& joint_group_name, Eigen::VectorXd& values) const
701  {
702  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
703  if (jmg)
704  copyJointGroupPositions(jmg, values);
705  }
706 
710  void copyJointGroupPositions(const JointModelGroup* group, Eigen::VectorXd& values) const;
711 
721  void setJointGroupVelocities(const std::string& joint_group_name, const double* gstate)
722  {
723  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
724  if (jmg)
725  setJointGroupVelocities(jmg, gstate);
726  }
727 
731  void setJointGroupVelocities(const std::string& joint_group_name, const std::vector<double>& gstate)
732  {
733  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
734  if (jmg)
735  setJointGroupVelocities(jmg, &gstate[0]);
736  }
737 
741  void setJointGroupVelocities(const JointModelGroup* group, const std::vector<double>& gstate)
742  {
743  setJointGroupVelocities(group, &gstate[0]);
744  }
745 
749  void setJointGroupVelocities(const JointModelGroup* group, const double* gstate);
750 
754  void setJointGroupVelocities(const std::string& joint_group_name, const Eigen::VectorXd& values)
755  {
756  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
757  if (jmg)
758  setJointGroupVelocities(jmg, values);
759  }
760 
764  void setJointGroupVelocities(const JointModelGroup* group, const Eigen::VectorXd& values);
765 
769  void copyJointGroupVelocities(const std::string& joint_group_name, std::vector<double>& gstate) const
770  {
771  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
772  if (jmg)
773  {
774  gstate.resize(jmg->getVariableCount());
775  copyJointGroupVelocities(jmg, &gstate[0]);
776  }
777  }
778 
782  void copyJointGroupVelocities(const std::string& joint_group_name, double* gstate) const
783  {
784  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
785  if (jmg)
786  copyJointGroupVelocities(jmg, gstate);
787  }
788 
792  void copyJointGroupVelocities(const JointModelGroup* group, std::vector<double>& gstate) const
793  {
794  gstate.resize(group->getVariableCount());
795  copyJointGroupVelocities(group, &gstate[0]);
796  }
797 
801  void copyJointGroupVelocities(const JointModelGroup* group, double* gstate) const;
802 
806  void copyJointGroupVelocities(const std::string& joint_group_name, Eigen::VectorXd& values) const
807  {
808  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
809  if (jmg)
810  copyJointGroupVelocities(jmg, values);
811  }
812 
816  void copyJointGroupVelocities(const JointModelGroup* group, Eigen::VectorXd& values) const;
817 
827  void setJointGroupAccelerations(const std::string& joint_group_name, const double* gstate)
828  {
829  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
830  if (jmg)
831  setJointGroupAccelerations(jmg, gstate);
832  }
833 
837  void setJointGroupAccelerations(const std::string& joint_group_name, const std::vector<double>& gstate)
838  {
839  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
840  if (jmg)
841  setJointGroupAccelerations(jmg, &gstate[0]);
842  }
843 
847  void setJointGroupAccelerations(const JointModelGroup* group, const std::vector<double>& gstate)
848  {
849  setJointGroupAccelerations(group, &gstate[0]);
850  }
851 
855  void setJointGroupAccelerations(const JointModelGroup* group, const double* gstate);
856 
860  void setJointGroupAccelerations(const std::string& joint_group_name, const Eigen::VectorXd& values)
861  {
862  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
863  if (jmg)
864  setJointGroupAccelerations(jmg, values);
865  }
866 
870  void setJointGroupAccelerations(const JointModelGroup* group, const Eigen::VectorXd& values);
871 
875  void copyJointGroupAccelerations(const std::string& joint_group_name, std::vector<double>& gstate) const
876  {
877  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
878  if (jmg)
879  {
880  gstate.resize(jmg->getVariableCount());
881  copyJointGroupAccelerations(jmg, &gstate[0]);
882  }
883  }
884 
888  void copyJointGroupAccelerations(const std::string& joint_group_name, double* gstate) const
889  {
890  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
891  if (jmg)
892  copyJointGroupAccelerations(jmg, gstate);
893  }
894 
898  void copyJointGroupAccelerations(const JointModelGroup* group, std::vector<double>& gstate) const
899  {
900  gstate.resize(group->getVariableCount());
901  copyJointGroupAccelerations(group, &gstate[0]);
902  }
903 
907  void copyJointGroupAccelerations(const JointModelGroup* group, double* gstate) const;
908 
912  void copyJointGroupAccelerations(const std::string& joint_group_name, Eigen::VectorXd& values) const
913  {
914  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
915  if (jmg)
916  copyJointGroupAccelerations(jmg, values);
917  }
918 
922  void copyJointGroupAccelerations(const JointModelGroup* group, Eigen::VectorXd& values) const;
923 
936  bool setToIKSolverFrame(Eigen::Affine3d& pose, const kinematics::KinematicsBaseConstPtr& solver);
937 
944  bool setToIKSolverFrame(Eigen::Affine3d& pose, const std::string& ik_frame);
945 
953  bool setFromIK(const JointModelGroup* group, const geometry_msgs::Pose& pose, unsigned int attempts = 0,
954  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
956 
965  bool setFromIK(const JointModelGroup* group, const geometry_msgs::Pose& pose, const std::string& tip,
966  unsigned int attempts = 0, double timeout = 0.0,
969 
977  bool setFromIK(const JointModelGroup* group, const Eigen::Affine3d& pose, unsigned int attempts = 0,
978  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
980 
988  bool setFromIK(const JointModelGroup* group, const Eigen::Affine3d& pose, const std::string& tip,
989  unsigned int attempts = 0, double timeout = 0.0,
992 
1002  bool setFromIK(const JointModelGroup* group, const Eigen::Affine3d& pose, const std::string& tip,
1003  const std::vector<double>& consistency_limits, unsigned int attempts = 0, double timeout = 0.0,
1006 
1017  bool setFromIK(const JointModelGroup* group, const EigenSTL::vector_Affine3d& poses,
1018  const std::vector<std::string>& tips, unsigned int attempts = 0, double timeout = 0.0,
1021 
1033  bool setFromIK(const JointModelGroup* group, const EigenSTL::vector_Affine3d& poses,
1034  const std::vector<std::string>& tips, const std::vector<std::vector<double> >& consistency_limits,
1035  unsigned int attempts = 0, double timeout = 0.0,
1038 
1048  bool setFromIKSubgroups(const JointModelGroup* group, const EigenSTL::vector_Affine3d& poses,
1049  const std::vector<std::string>& tips,
1050  const std::vector<std::vector<double> >& consistency_limits, unsigned int attempts = 0,
1051  double timeout = 0.0,
1054 
1062  bool setFromDiffIK(const JointModelGroup* group, const Eigen::VectorXd& twist, const std::string& tip, double dt,
1064 
1072  bool setFromDiffIK(const JointModelGroup* group, const geometry_msgs::Twist& twist, const std::string& tip, double dt,
1074 
1105  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1106  const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
1107  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
1110 
1111  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1112  const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
1113  double max_step, double jump_threshold_factor,
1116  {
1117  return computeCartesianPath(group, traj, link, direction, global_reference_frame, distance,
1118  MaxEEFStep(max_step, max_step), JumpThreshold(jump_threshold_factor), validCallback,
1119  options);
1120  }
1121 
1128  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1129  const Eigen::Affine3d& target, bool global_reference_frame, const MaxEEFStep& max_step,
1130  const JumpThreshold& jump_threshold,
1133 
1134  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1135  const Eigen::Affine3d& target, bool global_reference_frame, double max_step,
1136  double jump_threshold_factor,
1139  {
1140  return computeCartesianPath(group, traj, link, target, global_reference_frame, MaxEEFStep(max_step),
1141  JumpThreshold(jump_threshold_factor), validCallback, options);
1142  }
1143 
1150  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1151  const EigenSTL::vector_Affine3d& waypoints, bool global_reference_frame,
1152  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
1155 
1156  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1157  const EigenSTL::vector_Affine3d& waypoints, bool global_reference_frame, double max_step,
1158  double jump_threshold_factor,
1161  {
1162  return computeCartesianPath(group, traj, link, waypoints, global_reference_frame, MaxEEFStep(max_step),
1163  JumpThreshold(jump_threshold_factor), validCallback, options);
1164  }
1165 
1181  static double testJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1182  const JumpThreshold& jump_threshold);
1183 
1194  static double testRelativeJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1195  double jump_threshold_factor);
1196 
1209  static double testAbsoluteJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1210  double revolute_jump_threshold, double prismatic_jump_threshold);
1211 
1221  bool getJacobian(const JointModelGroup* group, const LinkModel* link, const Eigen::Vector3d& reference_point_position,
1222  Eigen::MatrixXd& jacobian, bool use_quaternion_representation = false) const;
1223 
1233  bool getJacobian(const JointModelGroup* group, const LinkModel* link, const Eigen::Vector3d& reference_point_position,
1234  Eigen::MatrixXd& jacobian, bool use_quaternion_representation = false)
1235  {
1236  updateLinkTransforms();
1237  return static_cast<const RobotState*>(this)->getJacobian(group, link, reference_point_position, jacobian,
1238  use_quaternion_representation);
1239  }
1240 
1247  Eigen::MatrixXd getJacobian(const JointModelGroup* group,
1248  const Eigen::Vector3d& reference_point_position = Eigen::Vector3d(0.0, 0.0, 0.0)) const;
1249 
1256  Eigen::MatrixXd getJacobian(const JointModelGroup* group,
1257  const Eigen::Vector3d& reference_point_position = Eigen::Vector3d(0.0, 0.0, 0.0))
1258  {
1259  updateLinkTransforms();
1260  return static_cast<const RobotState*>(this)->getJacobian(group, reference_point_position);
1261  }
1262 
1265  void computeVariableVelocity(const JointModelGroup* jmg, Eigen::VectorXd& qdot, const Eigen::VectorXd& twist,
1266  const LinkModel* tip) const;
1267 
1270  void computeVariableVelocity(const JointModelGroup* jmg, Eigen::VectorXd& qdot, const Eigen::VectorXd& twist,
1271  const LinkModel* tip)
1272  {
1273  updateLinkTransforms();
1274  static_cast<const RobotState*>(this)->computeVariableVelocity(jmg, qdot, twist, tip);
1275  }
1276 
1280  bool integrateVariableVelocity(const JointModelGroup* jmg, const Eigen::VectorXd& qdot, double dt,
1282 
1289  void setVariableValues(const sensor_msgs::JointState& msg)
1290  {
1291  if (!msg.position.empty())
1292  setVariablePositions(msg.name, msg.position);
1293  if (!msg.velocity.empty())
1294  setVariableVelocities(msg.name, msg.velocity);
1295  }
1296 
1300  void setToDefaultValues();
1301 
1303  bool setToDefaultValues(const JointModelGroup* group, const std::string& name);
1304 
1306  void setToRandomPositions();
1307 
1309  void setToRandomPositions(const JointModelGroup* group);
1310 
1313  void setToRandomPositions(const JointModelGroup* group, random_numbers::RandomNumberGenerator& rng);
1314 
1320  void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& near, double distance);
1321 
1329  void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& near,
1330  const std::vector<double>& distances);
1331 
1340  void updateCollisionBodyTransforms();
1341 
1344  void updateLinkTransforms();
1345 
1347  void update(bool force = false);
1348 
1357  void updateStateWithLinkAt(const std::string& link_name, const Eigen::Affine3d& transform, bool backward = false)
1358  {
1359  updateStateWithLinkAt(robot_model_->getLinkModel(link_name), transform, backward);
1360  }
1361 
1363  void updateStateWithLinkAt(const LinkModel* link, const Eigen::Affine3d& transform, bool backward = false);
1364 
1365  const Eigen::Affine3d& getGlobalLinkTransform(const std::string& link_name)
1366  {
1367  return getGlobalLinkTransform(robot_model_->getLinkModel(link_name));
1368  }
1369 
1370  const Eigen::Affine3d& getGlobalLinkTransform(const LinkModel* link)
1371  {
1372  updateLinkTransforms();
1373  return global_link_transforms_[link->getLinkIndex()];
1374  }
1375 
1376  const Eigen::Affine3d& getCollisionBodyTransforms(const std::string& link_name, std::size_t index)
1377  {
1378  return getCollisionBodyTransform(robot_model_->getLinkModel(link_name), index);
1379  }
1380 
1381  const Eigen::Affine3d& getCollisionBodyTransform(const LinkModel* link, std::size_t index)
1382  {
1383  updateCollisionBodyTransforms();
1384  return global_collision_body_transforms_[link->getFirstCollisionBodyTransformIndex() + index];
1385  }
1386 
1387  const Eigen::Affine3d& getJointTransform(const std::string& joint_name)
1388  {
1389  return getJointTransform(robot_model_->getJointModel(joint_name));
1390  }
1391 
1392  const Eigen::Affine3d& getJointTransform(const JointModel* joint)
1393  {
1394  const int idx = joint->getJointIndex();
1395  unsigned char& dirty = dirty_joint_transforms_[idx];
1396  if (dirty)
1397  {
1398  joint->computeTransform(position_ + joint->getFirstVariableIndex(), variable_joint_transforms_[idx]);
1399  dirty = 0;
1400  }
1401  return variable_joint_transforms_[idx];
1402  }
1403 
1404  const Eigen::Affine3d& getGlobalLinkTransform(const std::string& link_name) const
1405  {
1406  return getGlobalLinkTransform(robot_model_->getLinkModel(link_name));
1407  }
1408 
1409  const Eigen::Affine3d& getGlobalLinkTransform(const LinkModel* link) const
1410  {
1411  BOOST_VERIFY(checkLinkTransforms());
1412  return global_link_transforms_[link->getLinkIndex()];
1413  }
1414 
1415  const Eigen::Affine3d& getCollisionBodyTransform(const std::string& link_name, std::size_t index) const
1416  {
1417  return getCollisionBodyTransform(robot_model_->getLinkModel(link_name), index);
1418  }
1419 
1420  const Eigen::Affine3d& getCollisionBodyTransform(const LinkModel* link, std::size_t index) const
1421  {
1422  BOOST_VERIFY(checkCollisionTransforms());
1423  return global_collision_body_transforms_[link->getFirstCollisionBodyTransformIndex() + index];
1424  }
1425 
1426  const Eigen::Affine3d& getJointTransform(const std::string& joint_name) const
1427  {
1428  return getJointTransform(robot_model_->getJointModel(joint_name));
1429  }
1430 
1431  const Eigen::Affine3d& getJointTransform(const JointModel* joint) const
1432  {
1433  BOOST_VERIFY(checkJointTransforms(joint));
1434  return variable_joint_transforms_[joint->getJointIndex()];
1435  }
1436 
1437  bool dirtyJointTransform(const JointModel* joint) const
1438  {
1439  return dirty_joint_transforms_[joint->getJointIndex()];
1440  }
1441 
1442  bool dirtyLinkTransforms() const
1443  {
1444  return dirty_link_transforms_;
1445  }
1446 
1448  {
1449  return dirty_link_transforms_ || dirty_collision_body_transforms_;
1450  }
1451 
1453  bool dirty() const
1454  {
1455  return dirtyCollisionBodyTransforms();
1456  }
1457 
1464  double distance(const RobotState& other) const
1465  {
1466  return robot_model_->distance(position_, other.getVariablePositions());
1467  }
1468 
1469  double distance(const RobotState& other, const JointModelGroup* joint_group) const;
1470 
1471  double distance(const RobotState& other, const JointModel* joint) const
1472  {
1473  const int idx = joint->getFirstVariableIndex();
1474  return joint->distance(position_ + idx, other.position_ + idx);
1475  }
1476 
1480  void interpolate(const RobotState& to, double t, RobotState& state) const;
1481 
1485  void interpolate(const RobotState& to, double t, RobotState& state, const JointModelGroup* joint_group) const;
1486 
1490  void interpolate(const RobotState& to, double t, RobotState& state, const JointModel* joint) const
1491  {
1492  const int idx = joint->getFirstVariableIndex();
1493  joint->interpolate(position_ + idx, to.position_ + idx, t, state.position_ + idx);
1494  state.markDirtyJointTransforms(joint);
1495  state.updateMimicJoint(joint);
1496  }
1497 
1498  void enforceBounds();
1499  void enforceBounds(const JointModelGroup* joint_group);
1500  void enforceBounds(const JointModel* joint)
1501  {
1502  enforcePositionBounds(joint);
1503  if (has_velocity_)
1504  enforceVelocityBounds(joint);
1505  }
1507  {
1508  if (joint->enforcePositionBounds(position_ + joint->getFirstVariableIndex()))
1509  {
1510  markDirtyJointTransforms(joint);
1511  updateMimicJoint(joint);
1512  }
1513  }
1515  {
1516  joint->enforceVelocityBounds(velocity_ + joint->getFirstVariableIndex());
1517  }
1518 
1519  bool satisfiesBounds(double margin = 0.0) const;
1520  bool satisfiesBounds(const JointModelGroup* joint_group, double margin = 0.0) const;
1521  bool satisfiesBounds(const JointModel* joint, double margin = 0.0) const
1522  {
1523  return satisfiesPositionBounds(joint, margin) && (!has_velocity_ || satisfiesVelocityBounds(joint, margin));
1524  }
1525  bool satisfiesPositionBounds(const JointModel* joint, double margin = 0.0) const
1526  {
1527  return joint->satisfiesPositionBounds(getJointPositions(joint), margin);
1528  }
1529  bool satisfiesVelocityBounds(const JointModel* joint, double margin = 0.0) const
1530  {
1531  return joint->satisfiesVelocityBounds(getJointVelocities(joint), margin);
1532  }
1533 
1536  std::pair<double, const JointModel*> getMinDistanceToPositionBounds() const;
1537 
1540  std::pair<double, const JointModel*> getMinDistanceToPositionBounds(const JointModelGroup* group) const;
1541 
1544  std::pair<double, const JointModel*>
1545  getMinDistanceToPositionBounds(const std::vector<const JointModel*>& joints) const;
1546 
1553  bool isValidVelocityMove(const RobotState& other, const JointModelGroup* group, double dt) const;
1554 
1580  void attachBody(AttachedBody* attached_body);
1581 
1596  void attachBody(const std::string& id, const std::vector<shapes::ShapeConstPtr>& shapes,
1597  const EigenSTL::vector_Affine3d& attach_trans, const std::set<std::string>& touch_links,
1598  const std::string& link_name,
1599  const trajectory_msgs::JointTrajectory& detach_posture = trajectory_msgs::JointTrajectory());
1600 
1615  void attachBody(const std::string& id, const std::vector<shapes::ShapeConstPtr>& shapes,
1616  const EigenSTL::vector_Affine3d& attach_trans, const std::vector<std::string>& touch_links,
1617  const std::string& link_name,
1618  const trajectory_msgs::JointTrajectory& detach_posture = trajectory_msgs::JointTrajectory())
1619  {
1620  std::set<std::string> touch_links_set(touch_links.begin(), touch_links.end());
1621  attachBody(id, shapes, attach_trans, touch_links_set, link_name, detach_posture);
1622  }
1623 
1625  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies) const;
1626 
1628  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const JointModelGroup* lm) const;
1629 
1631  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const LinkModel* lm) const;
1632 
1635  bool clearAttachedBody(const std::string& id);
1636 
1638  void clearAttachedBodies(const LinkModel* link);
1639 
1641  void clearAttachedBodies(const JointModelGroup* group);
1642 
1644  void clearAttachedBodies();
1645 
1647  const AttachedBody* getAttachedBody(const std::string& name) const;
1648 
1650  bool hasAttachedBody(const std::string& id) const;
1651 
1652  void setAttachedBodyUpdateCallback(const AttachedBodyCallback& callback);
1657  void computeAABB(std::vector<double>& aabb) const;
1658 
1661  void computeAABB(std::vector<double>& aabb)
1662  {
1663  updateLinkTransforms();
1664  static_cast<const RobotState*>(this)->computeAABB(aabb);
1665  }
1666 
1669  {
1670  if (!rng_)
1672  return *rng_;
1673  }
1674 
1676  const Eigen::Affine3d& getFrameTransform(const std::string& id);
1677 
1679  const Eigen::Affine3d& getFrameTransform(const std::string& id) const;
1680 
1682  bool knowsFrameTransform(const std::string& id) const;
1683 
1691  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1692  const std_msgs::ColorRGBA& color, const std::string& ns, const ros::Duration& dur,
1693  bool include_attached = false) const;
1694 
1702  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1703  const std_msgs::ColorRGBA& color, const std::string& ns, const ros::Duration& dur,
1704  bool include_attached = false)
1705  {
1706  updateCollisionBodyTransforms();
1707  static_cast<const RobotState*>(this)->getRobotMarkers(arr, link_names, color, ns, dur, include_attached);
1708  }
1709 
1714  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1715  bool include_attached = false) const;
1716 
1721  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1722  bool include_attached = false)
1723  {
1724  updateCollisionBodyTransforms();
1725  static_cast<const RobotState*>(this)->getRobotMarkers(arr, link_names, include_attached);
1726  }
1727 
1728  void printStatePositions(std::ostream& out = std::cout) const;
1729 
1730  void printStateInfo(std::ostream& out = std::cout) const;
1731 
1732  void printTransforms(std::ostream& out = std::cout) const;
1733 
1734  void printTransform(const Eigen::Affine3d& transform, std::ostream& out = std::cout) const;
1735 
1736  void printDirtyInfo(std::ostream& out = std::cout) const;
1737 
1738  std::string getStateTreeString(const std::string& prefix = "") const;
1739 
1740 private:
1741  void allocMemory();
1742 
1743  void copyFrom(const RobotState& other);
1744 
1746  {
1747  dirty_joint_transforms_[joint->getJointIndex()] = 1;
1748  dirty_link_transforms_ =
1749  dirty_link_transforms_ == NULL ? joint : robot_model_->getCommonRoot(dirty_link_transforms_, joint);
1750  }
1751 
1753  {
1754  const std::vector<const JointModel*>& jm = group->getActiveJointModels();
1755  for (std::size_t i = 0; i < jm.size(); ++i)
1756  dirty_joint_transforms_[jm[i]->getJointIndex()] = 1;
1757  dirty_link_transforms_ = dirty_link_transforms_ == NULL ?
1758  group->getCommonRoot() :
1759  robot_model_->getCommonRoot(dirty_link_transforms_, group->getCommonRoot());
1760  }
1761 
1762  void markVelocity();
1763  void markAcceleration();
1764  void markEffort();
1765 
1766  void updateMimicJoint(const JointModel* joint)
1767  {
1768  const std::vector<const JointModel*>& mim = joint->getMimicRequests();
1769  double v = position_[joint->getFirstVariableIndex()];
1770  for (std::size_t i = 0; i < mim.size(); ++i)
1771  {
1772  position_[mim[i]->getFirstVariableIndex()] = mim[i]->getMimicFactor() * v + mim[i]->getMimicOffset();
1773  markDirtyJointTransforms(mim[i]);
1774  }
1775  }
1776 
1778  /* use updateMimicJoints() instead, which also marks joints dirty */
1779  MOVEIT_DEPRECATED void updateMimicJoint(const std::vector<const JointModel*>& mim)
1780  {
1781  for (std::size_t i = 0; i < mim.size(); ++i)
1782  {
1783  const int fvi = mim[i]->getFirstVariableIndex();
1784  position_[fvi] =
1785  mim[i]->getMimicFactor() * position_[mim[i]->getMimic()->getFirstVariableIndex()] + mim[i]->getMimicOffset();
1786  // Only mark joint transform dirty, but not the associated link transform
1787  // as this function is always used in combination of
1788  // updateMimicJoint(group->getMimicJointModels()) + markDirtyJointTransforms(group);
1789  dirty_joint_transforms_[mim[i]->getJointIndex()] = 1;
1790  }
1791  }
1792 
1795  {
1796  for (const JointModel* jm : group->getMimicJointModels())
1797  {
1798  const int fvi = jm->getFirstVariableIndex();
1799  position_[fvi] = jm->getMimicFactor() * position_[jm->getMimic()->getFirstVariableIndex()] + jm->getMimicOffset();
1800  markDirtyJointTransforms(jm);
1801  }
1802  markDirtyJointTransforms(group);
1803  }
1804 
1805  void updateLinkTransformsInternal(const JointModel* start);
1806 
1807  void getMissingKeys(const std::map<std::string, double>& variable_map,
1808  std::vector<std::string>& missing_variables) const;
1809  void getStateTreeJointString(std::ostream& ss, const JointModel* jm, const std::string& pfx0, bool last) const;
1810 
1812  bool checkJointTransforms(const JointModel* joint) const;
1813 
1815  bool checkLinkTransforms() const;
1816 
1818  bool checkCollisionTransforms() const;
1819 
1820  RobotModelConstPtr robot_model_;
1821  void* memory_;
1822 
1823  double* position_;
1824  double* velocity_;
1825  double* acceleration_;
1826  double* effort_;
1830 
1833 
1834  Eigen::Affine3d* variable_joint_transforms_; // this points to an element in transforms_, so it is aligned
1835  Eigen::Affine3d* global_link_transforms_; // this points to an element in transforms_, so it is aligned
1836  Eigen::Affine3d* global_collision_body_transforms_; // this points to an element in transforms_, so it is aligned
1837  unsigned char* dirty_joint_transforms_;
1838 
1840  std::map<std::string, AttachedBody*> attached_body_map_;
1841 
1845 
1852 };
1853 
1855 std::ostream& operator<<(std::ostream& out, const RobotState& s);
1856 }
1857 }
1858 
1859 #endif
void attachBody(const std::string &id, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Affine3d &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:1615
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:524
bool hasAccelerations() const
By default, if accelerations are never set or initialized, the state remembers that there are no acce...
Definition: robot_state.h:350
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:912
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:782
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
Definition: robot_state.h:1668
JumpThreshold(double jt_factor)
Definition: robot_state.h:81
A set of options for the kinematics solver.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Definition: joint_model.h:196
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:1661
void updateMimicJoint(const JointModel *joint)
Definition: robot_state.h:1766
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:806
Core components of MoveIt!
const Eigen::Affine3d & getGlobalLinkTransform(const LinkModel *link) const
Definition: robot_state.h:1409
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:1721
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:625
Eigen::Affine3d * global_collision_body_transforms_
Definition: robot_state.h:1836
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:827
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:888
ROSCPP_DECL void start()
double distance(const RobotState &other) const
Definition: robot_state.h:1464
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:676
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:898
const Eigen::Affine3d & getJointTransform(const JointModel *joint)
Definition: robot_state.h:1392
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
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:420
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:335
void updateMimicJoints(const JointModelGroup *group)
Update all mimic joints within group.
Definition: robot_state.h:1794
const Eigen::Affine3d & getGlobalLinkTransform(const std::string &link_name) const
Definition: robot_state.h:1404
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:450
const Eigen::Affine3d & getGlobalLinkTransform(const std::string &link_name)
Definition: robot_state.h:1365
void enforcePositionBounds(const JointModel *joint)
Definition: robot_state.h:1506
const Eigen::Affine3d & getJointTransform(const std::string &joint_name) const
Definition: robot_state.h:1426
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:383
const Eigen::Affine3d & getCollisionBodyTransform(const LinkModel *link, std::size_t index) const
Definition: robot_state.h:1420
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:875
const double * getJointVelocities(const std::string &joint_name) const
Definition: robot_state.h:576
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
Definition: robot_state.h:168
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:284
const JointModel * dirty_collision_body_transforms_
Definition: robot_state.h:1832
const Eigen::Affine3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index) const
Definition: robot_state.h:1415
#define MOVEIT_DEPRECATED
Definition: deprecation.h:48
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
Definition: robot_state.h:263
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:792
void enforceVelocityBounds(const JointModel *joint)
Definition: robot_state.h:1514
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:201
double computeCartesianPath(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, const LinkModel *link, const Eigen::Affine3d &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:1134
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
const std::vector< const JointModel * > & getMimicJointModels() const
Get the mimic joints that are part of this group.
void setJointPositions(const JointModel *joint, const double *position)
Definition: robot_state.h:539
Eigen::Affine3d * global_link_transforms_
Definition: robot_state.h:1835
const double * getJointEffort(const JointModel *joint) const
Definition: robot_state.h:601
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:721
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
Definition: joint_model.h:310
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:700
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:181
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:413
bool satisfiesBounds(const JointModel *joint, double margin=0.0) const
Definition: robot_state.h:1521
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
double computeCartesianPath(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, const LinkModel *link, const EigenSTL::vector_Affine3d &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:1156
void markDirtyJointTransforms(const JointModel *joint)
Definition: robot_state.h:1745
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:663
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:499
int getFirstCollisionBodyTransformIndex() const
Definition: link_model.h:97
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:635
void setJointPositions(const std::string &joint_name, const std::vector< double > &position)
Definition: robot_state.h:529
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...
bool satisfiesVelocityBounds(const JointModel *joint, double margin=0.0) const
Definition: robot_state.h:1529
bool satisfiesPositionBounds(const JointModel *joint, double margin=0.0) const
Definition: robot_state.h:1525
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:1256
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
const double * getJointEffort(const std::string &joint_name) const
Definition: robot_state.h:596
const Eigen::Affine3d & getJointTransform(const JointModel *joint) const
Definition: robot_state.h:1431
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:741
int getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
Definition: link_model.h:87
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:492
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:731
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:837
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:473
const Eigen::Affine3d & getCollisionBodyTransforms(const std::string &link_name, std::size_t index)
Definition: robot_state.h:1376
void enforceBounds(const JointModel *joint)
Definition: robot_state.h:1500
int getJointIndex() const
Get the index of this joint within the robot model.
Definition: joint_model.h:214
Struct for containing jump_threshold.
Definition: robot_state.h:71
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) ...
MOVEIT_CLASS_FORWARD(RobotModel)
MaxEEFStep(double translation=0.0, double rotation=0.0)
Definition: robot_state.h:98
void setJointPositions(const JointModel *joint, const std::vector< double > &position)
Definition: robot_state.h:534
boost::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
Definition: attached_body.h:50
double distance(const RobotState &other, const JointModel *joint) const
Definition: robot_state.h:1471
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:384
const Eigen::Affine3d & getCollisionBodyTransform(const LinkModel *link, std::size_t index)
Definition: robot_state.h:1381
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:754
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:1233
unsigned char * dirty_joint_transforms_
Definition: robot_state.h:1837
bool dirtyLinkTransforms() const
Definition: robot_state.h:1442
void updateStateWithLinkAt(const std::string &link_name, const Eigen::Affine3d &transform, bool backward=false)
Update the state after setting a particular link to the input global transform pose.
Definition: robot_state.h:1357
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:1844
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:860
const double * getVariablePositions() const
Get a raw pointer to the positions of the variables stored in this state.
Definition: robot_state.h:188
Struct for containing max_step for computeCartesianPath.
Definition: robot_state.h:96
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:648
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:1702
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
Definition: robot_state.h:138
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:249
void markDirtyJointTransforms(const JointModelGroup *group)
Definition: robot_state.h:1752
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:270
const JointModel * getJointModel(const std::string &joint) const
Get the model of a particular joint.
Definition: robot_state.h:162
const JointModel * getCommonRoot() const
Get the common root of all joint roots; not necessarily part of this group.
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:320
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:1270
JumpThreshold(double jt_revolute, double jt_prismatic)
Definition: robot_state.h:86
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:769
virtual void computeTransform(const double *joint_values, Eigen::Affine3d &transf) const =0
Given the joint values for a joint, compute the corresponding transform.
const JointModel * dirty_link_transforms_
Definition: robot_state.h:1831
int getFirstVariableIndex() const
Get the index of this joint&#39;s first variable within the full robot state.
Definition: joint_model.h:202
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:428
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:358
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
Definition: robot_state.h:156
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:615
const double * getJointAccelerations(const JointModel *joint) const
Definition: robot_state.h:591
random_numbers::RandomNumberGenerator * rng_
For certain operations a state needs a random number generator. However, it may be slightly expensive...
Definition: robot_state.h:1851
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:442
void setJointPositions(const JointModel *joint, const Eigen::Affine3d &transform)
Definition: robot_state.h:551
RobotModelConstPtr robot_model_
Definition: robot_state.h:1820
void setVariableValues(const sensor_msgs::JointState &msg)
Definition: robot_state.h:1289
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:373
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:1490
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:278
const double * getJointVelocities(const JointModel *joint) const
Definition: robot_state.h:581
const Eigen::Affine3d & getJointTransform(const std::string &joint_name)
Definition: robot_state.h:1387
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:123
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 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:406
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:241
A link from the robot. Contains the constant transform applied to the link and its geometry...
Definition: link_model.h:72
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:458
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:464
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:366
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:150
bool dirty() const
Returns true if anything in this state is dirty.
Definition: robot_state.h:1453
bool dirtyJointTransform(const JointModel *joint) const
Definition: robot_state.h:1437
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:847
const double * getJointPositions(const std::string &joint_name) const
Definition: robot_state.h:566
const double * getJointAccelerations(const std::string &joint_name) const
Definition: robot_state.h:586
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:222
Main namespace for MoveIt!
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:686
const Eigen::Affine3d & getGlobalLinkTransform(const LinkModel *link)
Definition: robot_state.h:1370
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:514
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:301
std::size_t getVariableCount() const
Get the number of variables that make up this state.
Definition: robot_state.h:144
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:327
Object defining bodies that can be attached to robot links. This is useful when handling objects pick...
Definition: attached_body.h:56
Eigen::Affine3d * variable_joint_transforms_
Definition: robot_state.h:1834
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
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:229
bool dirtyCollisionBodyTransforms() const
Definition: robot_state.h:1447
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:292
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:313
virtual void computeVariablePositions(const Eigen::Affine3d &transform, double *joint_values) const =0
Given the transform generated by joint, compute the corresponding joint values.
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
const double * getJointPositions(const JointModel *joint) const
Definition: robot_state.h:571
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:64
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:1111
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:1840
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:506
void setJointPositions(const std::string &joint_name, const Eigen::Affine3d &transform)
Definition: robot_state.h:546
MOVEIT_DEPRECATED 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:1779
void setJointVelocities(const JointModel *joint, const double *velocity)
Definition: robot_state.h:558


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Oct 18 2018 02:47:09