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 
520  void invertVelocity();
521 
527  void setJointPositions(const std::string& joint_name, const double* position)
528  {
529  setJointPositions(robot_model_->getJointModel(joint_name), position);
530  }
531 
532  void setJointPositions(const std::string& joint_name, const std::vector<double>& position)
533  {
534  setJointPositions(robot_model_->getJointModel(joint_name), &position[0]);
535  }
536 
537  void setJointPositions(const JointModel* joint, const std::vector<double>& position)
538  {
539  setJointPositions(joint, &position[0]);
540  }
541 
542  void setJointPositions(const JointModel* joint, const double* position)
543  {
544  memcpy(position_ + joint->getFirstVariableIndex(), position, joint->getVariableCount() * sizeof(double));
545  markDirtyJointTransforms(joint);
546  updateMimicJoint(joint);
547  }
548 
549  void setJointPositions(const std::string& joint_name, const Eigen::Affine3d& transform)
550  {
551  setJointPositions(robot_model_->getJointModel(joint_name), transform);
552  }
553 
554  void setJointPositions(const JointModel* joint, const Eigen::Affine3d& transform)
555  {
556  joint->computeVariablePositions(transform, position_ + joint->getFirstVariableIndex());
557  markDirtyJointTransforms(joint);
558  updateMimicJoint(joint);
559  }
560 
561  void setJointVelocities(const JointModel* joint, const double* velocity)
562  {
563  has_velocity_ = true;
564  memcpy(velocity_ + joint->getFirstVariableIndex(), velocity, joint->getVariableCount() * sizeof(double));
565  }
566 
567  void setJointEfforts(const JointModel* joint, const double* effort);
568 
569  const double* getJointPositions(const std::string& joint_name) const
570  {
571  return getJointPositions(robot_model_->getJointModel(joint_name));
572  }
573 
574  const double* getJointPositions(const JointModel* joint) const
575  {
576  return position_ + joint->getFirstVariableIndex();
577  }
578 
579  const double* getJointVelocities(const std::string& joint_name) const
580  {
581  return getJointVelocities(robot_model_->getJointModel(joint_name));
582  }
583 
584  const double* getJointVelocities(const JointModel* joint) const
585  {
586  return velocity_ + joint->getFirstVariableIndex();
587  }
588 
589  const double* getJointAccelerations(const std::string& joint_name) const
590  {
591  return getJointAccelerations(robot_model_->getJointModel(joint_name));
592  }
593 
594  const double* getJointAccelerations(const JointModel* joint) const
595  {
596  return acceleration_ + joint->getFirstVariableIndex();
597  }
598 
599  const double* getJointEffort(const std::string& joint_name) const
600  {
601  return getJointEffort(robot_model_->getJointModel(joint_name));
602  }
603 
604  const double* getJointEffort(const JointModel* joint) const
605  {
606  return effort_ + joint->getFirstVariableIndex();
607  }
608 
618  void setJointGroupPositions(const std::string& joint_group_name, const double* gstate)
619  {
620  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
621  if (jmg)
622  setJointGroupPositions(jmg, gstate);
623  }
624 
628  void setJointGroupPositions(const std::string& joint_group_name, const std::vector<double>& gstate)
629  {
630  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
631  if (jmg)
632  setJointGroupPositions(jmg, &gstate[0]);
633  }
634 
638  void setJointGroupPositions(const JointModelGroup* group, const std::vector<double>& gstate)
639  {
640  setJointGroupPositions(group, &gstate[0]);
641  }
642 
646  void setJointGroupPositions(const JointModelGroup* group, const double* gstate);
647 
651  void setJointGroupPositions(const std::string& joint_group_name, const Eigen::VectorXd& values)
652  {
653  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
654  if (jmg)
655  setJointGroupPositions(jmg, values);
656  }
657 
661  void setJointGroupPositions(const JointModelGroup* group, const Eigen::VectorXd& values);
662 
666  void copyJointGroupPositions(const std::string& joint_group_name, std::vector<double>& gstate) const
667  {
668  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
669  if (jmg)
670  {
671  gstate.resize(jmg->getVariableCount());
672  copyJointGroupPositions(jmg, &gstate[0]);
673  }
674  }
675 
679  void copyJointGroupPositions(const std::string& joint_group_name, double* gstate) const
680  {
681  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
682  if (jmg)
683  copyJointGroupPositions(jmg, gstate);
684  }
685 
689  void copyJointGroupPositions(const JointModelGroup* group, std::vector<double>& gstate) const
690  {
691  gstate.resize(group->getVariableCount());
692  copyJointGroupPositions(group, &gstate[0]);
693  }
694 
698  void copyJointGroupPositions(const JointModelGroup* group, double* gstate) const;
699 
703  void copyJointGroupPositions(const std::string& joint_group_name, Eigen::VectorXd& values) const
704  {
705  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
706  if (jmg)
707  copyJointGroupPositions(jmg, values);
708  }
709 
713  void copyJointGroupPositions(const JointModelGroup* group, Eigen::VectorXd& values) const;
714 
724  void setJointGroupVelocities(const std::string& joint_group_name, const double* gstate)
725  {
726  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
727  if (jmg)
728  setJointGroupVelocities(jmg, gstate);
729  }
730 
734  void setJointGroupVelocities(const std::string& joint_group_name, const std::vector<double>& gstate)
735  {
736  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
737  if (jmg)
738  setJointGroupVelocities(jmg, &gstate[0]);
739  }
740 
744  void setJointGroupVelocities(const JointModelGroup* group, const std::vector<double>& gstate)
745  {
746  setJointGroupVelocities(group, &gstate[0]);
747  }
748 
752  void setJointGroupVelocities(const JointModelGroup* group, const double* gstate);
753 
757  void setJointGroupVelocities(const std::string& joint_group_name, const Eigen::VectorXd& values)
758  {
759  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
760  if (jmg)
761  setJointGroupVelocities(jmg, values);
762  }
763 
767  void setJointGroupVelocities(const JointModelGroup* group, const Eigen::VectorXd& values);
768 
772  void copyJointGroupVelocities(const std::string& joint_group_name, std::vector<double>& gstate) const
773  {
774  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
775  if (jmg)
776  {
777  gstate.resize(jmg->getVariableCount());
778  copyJointGroupVelocities(jmg, &gstate[0]);
779  }
780  }
781 
785  void copyJointGroupVelocities(const std::string& joint_group_name, double* gstate) const
786  {
787  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
788  if (jmg)
789  copyJointGroupVelocities(jmg, gstate);
790  }
791 
795  void copyJointGroupVelocities(const JointModelGroup* group, std::vector<double>& gstate) const
796  {
797  gstate.resize(group->getVariableCount());
798  copyJointGroupVelocities(group, &gstate[0]);
799  }
800 
804  void copyJointGroupVelocities(const JointModelGroup* group, double* gstate) const;
805 
809  void copyJointGroupVelocities(const std::string& joint_group_name, Eigen::VectorXd& values) const
810  {
811  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
812  if (jmg)
813  copyJointGroupVelocities(jmg, values);
814  }
815 
819  void copyJointGroupVelocities(const JointModelGroup* group, Eigen::VectorXd& values) const;
820 
830  void setJointGroupAccelerations(const std::string& joint_group_name, const double* gstate)
831  {
832  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
833  if (jmg)
834  setJointGroupAccelerations(jmg, gstate);
835  }
836 
840  void setJointGroupAccelerations(const std::string& joint_group_name, const std::vector<double>& gstate)
841  {
842  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
843  if (jmg)
844  setJointGroupAccelerations(jmg, &gstate[0]);
845  }
846 
850  void setJointGroupAccelerations(const JointModelGroup* group, const std::vector<double>& gstate)
851  {
852  setJointGroupAccelerations(group, &gstate[0]);
853  }
854 
858  void setJointGroupAccelerations(const JointModelGroup* group, const double* gstate);
859 
863  void setJointGroupAccelerations(const std::string& joint_group_name, const Eigen::VectorXd& values)
864  {
865  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
866  if (jmg)
867  setJointGroupAccelerations(jmg, values);
868  }
869 
873  void setJointGroupAccelerations(const JointModelGroup* group, const Eigen::VectorXd& values);
874 
878  void copyJointGroupAccelerations(const std::string& joint_group_name, std::vector<double>& gstate) const
879  {
880  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
881  if (jmg)
882  {
883  gstate.resize(jmg->getVariableCount());
884  copyJointGroupAccelerations(jmg, &gstate[0]);
885  }
886  }
887 
891  void copyJointGroupAccelerations(const std::string& joint_group_name, double* gstate) const
892  {
893  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
894  if (jmg)
895  copyJointGroupAccelerations(jmg, gstate);
896  }
897 
901  void copyJointGroupAccelerations(const JointModelGroup* group, std::vector<double>& gstate) const
902  {
903  gstate.resize(group->getVariableCount());
904  copyJointGroupAccelerations(group, &gstate[0]);
905  }
906 
910  void copyJointGroupAccelerations(const JointModelGroup* group, double* gstate) const;
911 
915  void copyJointGroupAccelerations(const std::string& joint_group_name, Eigen::VectorXd& values) const
916  {
917  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
918  if (jmg)
919  copyJointGroupAccelerations(jmg, values);
920  }
921 
925  void copyJointGroupAccelerations(const JointModelGroup* group, Eigen::VectorXd& values) const;
926 
939  bool setToIKSolverFrame(Eigen::Affine3d& pose, const kinematics::KinematicsBaseConstPtr& solver);
940 
947  bool setToIKSolverFrame(Eigen::Affine3d& pose, const std::string& ik_frame);
948 
956  bool setFromIK(const JointModelGroup* group, const geometry_msgs::Pose& pose, unsigned int attempts = 0,
957  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
959 
968  bool setFromIK(const JointModelGroup* group, const geometry_msgs::Pose& pose, const std::string& tip,
969  unsigned int attempts = 0, double timeout = 0.0,
972 
980  bool setFromIK(const JointModelGroup* group, const Eigen::Affine3d& pose, unsigned int attempts = 0,
981  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
983 
991  bool setFromIK(const JointModelGroup* group, const Eigen::Affine3d& pose, const std::string& tip,
992  unsigned int attempts = 0, double timeout = 0.0,
995 
1005  bool setFromIK(const JointModelGroup* group, const Eigen::Affine3d& pose, const std::string& tip,
1006  const std::vector<double>& consistency_limits, unsigned int attempts = 0, double timeout = 0.0,
1009 
1020  bool setFromIK(const JointModelGroup* group, const EigenSTL::vector_Affine3d& poses,
1021  const std::vector<std::string>& tips, unsigned int attempts = 0, double timeout = 0.0,
1024 
1036  bool setFromIK(const JointModelGroup* group, const EigenSTL::vector_Affine3d& poses,
1037  const std::vector<std::string>& tips, const std::vector<std::vector<double> >& consistency_limits,
1038  unsigned int attempts = 0, double timeout = 0.0,
1041 
1051  bool setFromIKSubgroups(const JointModelGroup* group, const EigenSTL::vector_Affine3d& poses,
1052  const std::vector<std::string>& tips,
1053  const std::vector<std::vector<double> >& consistency_limits, unsigned int attempts = 0,
1054  double timeout = 0.0,
1057 
1065  bool setFromDiffIK(const JointModelGroup* group, const Eigen::VectorXd& twist, const std::string& tip, double dt,
1067 
1075  bool setFromDiffIK(const JointModelGroup* group, const geometry_msgs::Twist& twist, const std::string& tip, double dt,
1077 
1108  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1109  const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
1110  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
1113 
1114  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1115  const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
1116  double max_step, double jump_threshold_factor,
1119  {
1120  return computeCartesianPath(group, traj, link, direction, global_reference_frame, distance,
1121  MaxEEFStep(max_step, max_step), JumpThreshold(jump_threshold_factor), validCallback,
1122  options);
1123  }
1124 
1131  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1132  const Eigen::Affine3d& target, bool global_reference_frame, const MaxEEFStep& max_step,
1133  const JumpThreshold& jump_threshold,
1136 
1137  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1138  const Eigen::Affine3d& target, bool global_reference_frame, double max_step,
1139  double jump_threshold_factor,
1142  {
1143  return computeCartesianPath(group, traj, link, target, global_reference_frame, MaxEEFStep(max_step),
1144  JumpThreshold(jump_threshold_factor), validCallback, options);
1145  }
1146 
1153  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1154  const EigenSTL::vector_Affine3d& waypoints, bool global_reference_frame,
1155  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
1158 
1159  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1160  const EigenSTL::vector_Affine3d& waypoints, bool global_reference_frame, double max_step,
1161  double jump_threshold_factor,
1164  {
1165  return computeCartesianPath(group, traj, link, waypoints, global_reference_frame, MaxEEFStep(max_step),
1166  JumpThreshold(jump_threshold_factor), validCallback, options);
1167  }
1168 
1184  static double testJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1185  const JumpThreshold& jump_threshold);
1186 
1197  static double testRelativeJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1198  double jump_threshold_factor);
1199 
1212  static double testAbsoluteJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1213  double revolute_jump_threshold, double prismatic_jump_threshold);
1214 
1224  bool getJacobian(const JointModelGroup* group, const LinkModel* link, const Eigen::Vector3d& reference_point_position,
1225  Eigen::MatrixXd& jacobian, bool use_quaternion_representation = false) const;
1226 
1236  bool getJacobian(const JointModelGroup* group, const LinkModel* link, const Eigen::Vector3d& reference_point_position,
1237  Eigen::MatrixXd& jacobian, bool use_quaternion_representation = false)
1238  {
1239  updateLinkTransforms();
1240  return static_cast<const RobotState*>(this)->getJacobian(group, link, reference_point_position, jacobian,
1241  use_quaternion_representation);
1242  }
1243 
1250  Eigen::MatrixXd getJacobian(const JointModelGroup* group,
1251  const Eigen::Vector3d& reference_point_position = Eigen::Vector3d(0.0, 0.0, 0.0)) const;
1252 
1259  Eigen::MatrixXd getJacobian(const JointModelGroup* group,
1260  const Eigen::Vector3d& reference_point_position = Eigen::Vector3d(0.0, 0.0, 0.0))
1261  {
1262  updateLinkTransforms();
1263  return static_cast<const RobotState*>(this)->getJacobian(group, reference_point_position);
1264  }
1265 
1268  void computeVariableVelocity(const JointModelGroup* jmg, Eigen::VectorXd& qdot, const Eigen::VectorXd& twist,
1269  const LinkModel* tip) const;
1270 
1273  void computeVariableVelocity(const JointModelGroup* jmg, Eigen::VectorXd& qdot, const Eigen::VectorXd& twist,
1274  const LinkModel* tip)
1275  {
1276  updateLinkTransforms();
1277  static_cast<const RobotState*>(this)->computeVariableVelocity(jmg, qdot, twist, tip);
1278  }
1279 
1283  bool integrateVariableVelocity(const JointModelGroup* jmg, const Eigen::VectorXd& qdot, double dt,
1285 
1292  void setVariableValues(const sensor_msgs::JointState& msg)
1293  {
1294  if (!msg.position.empty())
1295  setVariablePositions(msg.name, msg.position);
1296  if (!msg.velocity.empty())
1297  setVariableVelocities(msg.name, msg.velocity);
1298  }
1299 
1303  void setToDefaultValues();
1304 
1306  bool setToDefaultValues(const JointModelGroup* group, const std::string& name);
1307 
1309  void setToRandomPositions();
1310 
1312  void setToRandomPositions(const JointModelGroup* group);
1313 
1316  void setToRandomPositions(const JointModelGroup* group, random_numbers::RandomNumberGenerator& rng);
1317 
1323  void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& near, double distance);
1324 
1332  void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& near,
1333  const std::vector<double>& distances);
1334 
1343  void updateCollisionBodyTransforms();
1344 
1347  void updateLinkTransforms();
1348 
1350  void update(bool force = false);
1351 
1360  void updateStateWithLinkAt(const std::string& link_name, const Eigen::Affine3d& transform, bool backward = false)
1361  {
1362  updateStateWithLinkAt(robot_model_->getLinkModel(link_name), transform, backward);
1363  }
1364 
1366  void updateStateWithLinkAt(const LinkModel* link, const Eigen::Affine3d& transform, bool backward = false);
1367 
1368  const Eigen::Affine3d& getGlobalLinkTransform(const std::string& link_name)
1369  {
1370  return getGlobalLinkTransform(robot_model_->getLinkModel(link_name));
1371  }
1372 
1373  const Eigen::Affine3d& getGlobalLinkTransform(const LinkModel* link)
1374  {
1375  updateLinkTransforms();
1376  return global_link_transforms_[link->getLinkIndex()];
1377  }
1378 
1379  const Eigen::Affine3d& getCollisionBodyTransforms(const std::string& link_name, std::size_t index)
1380  {
1381  return getCollisionBodyTransform(robot_model_->getLinkModel(link_name), index);
1382  }
1383 
1384  const Eigen::Affine3d& getCollisionBodyTransform(const LinkModel* link, std::size_t index)
1385  {
1386  updateCollisionBodyTransforms();
1387  return global_collision_body_transforms_[link->getFirstCollisionBodyTransformIndex() + index];
1388  }
1389 
1390  const Eigen::Affine3d& getJointTransform(const std::string& joint_name)
1391  {
1392  return getJointTransform(robot_model_->getJointModel(joint_name));
1393  }
1394 
1395  const Eigen::Affine3d& getJointTransform(const JointModel* joint)
1396  {
1397  const int idx = joint->getJointIndex();
1398  unsigned char& dirty = dirty_joint_transforms_[idx];
1399  if (dirty)
1400  {
1401  joint->computeTransform(position_ + joint->getFirstVariableIndex(), variable_joint_transforms_[idx]);
1402  dirty = 0;
1403  }
1404  return variable_joint_transforms_[idx];
1405  }
1406 
1407  const Eigen::Affine3d& getGlobalLinkTransform(const std::string& link_name) const
1408  {
1409  return getGlobalLinkTransform(robot_model_->getLinkModel(link_name));
1410  }
1411 
1412  const Eigen::Affine3d& getGlobalLinkTransform(const LinkModel* link) const
1413  {
1414  BOOST_VERIFY(checkLinkTransforms());
1415  return global_link_transforms_[link->getLinkIndex()];
1416  }
1417 
1418  const Eigen::Affine3d& getCollisionBodyTransform(const std::string& link_name, std::size_t index) const
1419  {
1420  return getCollisionBodyTransform(robot_model_->getLinkModel(link_name), index);
1421  }
1422 
1423  const Eigen::Affine3d& getCollisionBodyTransform(const LinkModel* link, std::size_t index) const
1424  {
1425  BOOST_VERIFY(checkCollisionTransforms());
1426  return global_collision_body_transforms_[link->getFirstCollisionBodyTransformIndex() + index];
1427  }
1428 
1429  const Eigen::Affine3d& getJointTransform(const std::string& joint_name) const
1430  {
1431  return getJointTransform(robot_model_->getJointModel(joint_name));
1432  }
1433 
1434  const Eigen::Affine3d& getJointTransform(const JointModel* joint) const
1435  {
1436  BOOST_VERIFY(checkJointTransforms(joint));
1437  return variable_joint_transforms_[joint->getJointIndex()];
1438  }
1439 
1440  bool dirtyJointTransform(const JointModel* joint) const
1441  {
1442  return dirty_joint_transforms_[joint->getJointIndex()];
1443  }
1444 
1445  bool dirtyLinkTransforms() const
1446  {
1447  return dirty_link_transforms_;
1448  }
1449 
1451  {
1452  return dirty_link_transforms_ || dirty_collision_body_transforms_;
1453  }
1454 
1456  bool dirty() const
1457  {
1458  return dirtyCollisionBodyTransforms();
1459  }
1460 
1467  double distance(const RobotState& other) const
1468  {
1469  return robot_model_->distance(position_, other.getVariablePositions());
1470  }
1471 
1472  double distance(const RobotState& other, const JointModelGroup* joint_group) const;
1473 
1474  double distance(const RobotState& other, const JointModel* joint) const
1475  {
1476  const int idx = joint->getFirstVariableIndex();
1477  return joint->distance(position_ + idx, other.position_ + idx);
1478  }
1479 
1483  void interpolate(const RobotState& to, double t, RobotState& state) const;
1484 
1488  void interpolate(const RobotState& to, double t, RobotState& state, const JointModelGroup* joint_group) const;
1489 
1493  void interpolate(const RobotState& to, double t, RobotState& state, const JointModel* joint) const
1494  {
1495  const int idx = joint->getFirstVariableIndex();
1496  joint->interpolate(position_ + idx, to.position_ + idx, t, state.position_ + idx);
1497  state.markDirtyJointTransforms(joint);
1498  state.updateMimicJoint(joint);
1499  }
1500 
1501  void enforceBounds();
1502  void enforceBounds(const JointModelGroup* joint_group);
1503  void enforceBounds(const JointModel* joint)
1504  {
1505  enforcePositionBounds(joint);
1506  if (has_velocity_)
1507  enforceVelocityBounds(joint);
1508  }
1510  {
1511  if (joint->enforcePositionBounds(position_ + joint->getFirstVariableIndex()))
1512  {
1513  markDirtyJointTransforms(joint);
1514  updateMimicJoint(joint);
1515  }
1516  }
1518  {
1519  joint->enforceVelocityBounds(velocity_ + joint->getFirstVariableIndex());
1520  }
1521 
1522  bool satisfiesBounds(double margin = 0.0) const;
1523  bool satisfiesBounds(const JointModelGroup* joint_group, double margin = 0.0) const;
1524  bool satisfiesBounds(const JointModel* joint, double margin = 0.0) const
1525  {
1526  return satisfiesPositionBounds(joint, margin) && (!has_velocity_ || satisfiesVelocityBounds(joint, margin));
1527  }
1528  bool satisfiesPositionBounds(const JointModel* joint, double margin = 0.0) const
1529  {
1530  return joint->satisfiesPositionBounds(getJointPositions(joint), margin);
1531  }
1532  bool satisfiesVelocityBounds(const JointModel* joint, double margin = 0.0) const
1533  {
1534  return joint->satisfiesVelocityBounds(getJointVelocities(joint), margin);
1535  }
1536 
1539  std::pair<double, const JointModel*> getMinDistanceToPositionBounds() const;
1540 
1543  std::pair<double, const JointModel*> getMinDistanceToPositionBounds(const JointModelGroup* group) const;
1544 
1547  std::pair<double, const JointModel*>
1548  getMinDistanceToPositionBounds(const std::vector<const JointModel*>& joints) const;
1549 
1556  bool isValidVelocityMove(const RobotState& other, const JointModelGroup* group, double dt) const;
1557 
1583  void attachBody(AttachedBody* attached_body);
1584 
1599  void attachBody(const std::string& id, const std::vector<shapes::ShapeConstPtr>& shapes,
1600  const EigenSTL::vector_Affine3d& attach_trans, const std::set<std::string>& touch_links,
1601  const std::string& link_name,
1602  const trajectory_msgs::JointTrajectory& detach_posture = trajectory_msgs::JointTrajectory());
1603 
1618  void attachBody(const std::string& id, const std::vector<shapes::ShapeConstPtr>& shapes,
1619  const EigenSTL::vector_Affine3d& attach_trans, const std::vector<std::string>& touch_links,
1620  const std::string& link_name,
1621  const trajectory_msgs::JointTrajectory& detach_posture = trajectory_msgs::JointTrajectory())
1622  {
1623  std::set<std::string> touch_links_set(touch_links.begin(), touch_links.end());
1624  attachBody(id, shapes, attach_trans, touch_links_set, link_name, detach_posture);
1625  }
1626 
1628  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies) const;
1629 
1631  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const JointModelGroup* lm) const;
1632 
1634  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const LinkModel* lm) const;
1635 
1638  bool clearAttachedBody(const std::string& id);
1639 
1641  void clearAttachedBodies(const LinkModel* link);
1642 
1644  void clearAttachedBodies(const JointModelGroup* group);
1645 
1647  void clearAttachedBodies();
1648 
1650  const AttachedBody* getAttachedBody(const std::string& name) const;
1651 
1653  bool hasAttachedBody(const std::string& id) const;
1654 
1655  void setAttachedBodyUpdateCallback(const AttachedBodyCallback& callback);
1660  void computeAABB(std::vector<double>& aabb) const;
1661 
1664  void computeAABB(std::vector<double>& aabb)
1665  {
1666  updateLinkTransforms();
1667  static_cast<const RobotState*>(this)->computeAABB(aabb);
1668  }
1669 
1672  {
1673  if (!rng_)
1675  return *rng_;
1676  }
1677 
1679  const Eigen::Affine3d& getFrameTransform(const std::string& id);
1680 
1682  const Eigen::Affine3d& getFrameTransform(const std::string& id) const;
1683 
1685  bool knowsFrameTransform(const std::string& id) const;
1686 
1694  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1695  const std_msgs::ColorRGBA& color, const std::string& ns, const ros::Duration& dur,
1696  bool include_attached = false) const;
1697 
1705  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1706  const std_msgs::ColorRGBA& color, const std::string& ns, const ros::Duration& dur,
1707  bool include_attached = false)
1708  {
1709  updateCollisionBodyTransforms();
1710  static_cast<const RobotState*>(this)->getRobotMarkers(arr, link_names, color, ns, dur, include_attached);
1711  }
1712 
1717  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1718  bool include_attached = false) const;
1719 
1724  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1725  bool include_attached = false)
1726  {
1727  updateCollisionBodyTransforms();
1728  static_cast<const RobotState*>(this)->getRobotMarkers(arr, link_names, include_attached);
1729  }
1730 
1731  void printStatePositions(std::ostream& out = std::cout) const;
1732 
1733  void printStateInfo(std::ostream& out = std::cout) const;
1734 
1735  void printTransforms(std::ostream& out = std::cout) const;
1736 
1737  void printTransform(const Eigen::Affine3d& transform, std::ostream& out = std::cout) const;
1738 
1739  void printDirtyInfo(std::ostream& out = std::cout) const;
1740 
1741  std::string getStateTreeString(const std::string& prefix = "") const;
1742 
1743 private:
1744  void allocMemory();
1745 
1746  void copyFrom(const RobotState& other);
1747 
1749  {
1750  dirty_joint_transforms_[joint->getJointIndex()] = 1;
1751  dirty_link_transforms_ =
1752  dirty_link_transforms_ == NULL ? joint : robot_model_->getCommonRoot(dirty_link_transforms_, joint);
1753  }
1754 
1756  {
1757  const std::vector<const JointModel*>& jm = group->getActiveJointModels();
1758  for (std::size_t i = 0; i < jm.size(); ++i)
1759  dirty_joint_transforms_[jm[i]->getJointIndex()] = 1;
1760  dirty_link_transforms_ = dirty_link_transforms_ == NULL ?
1761  group->getCommonRoot() :
1762  robot_model_->getCommonRoot(dirty_link_transforms_, group->getCommonRoot());
1763  }
1764 
1765  void markVelocity();
1766  void markAcceleration();
1767  void markEffort();
1768 
1769  void updateMimicJoint(const JointModel* joint)
1770  {
1771  const std::vector<const JointModel*>& mim = joint->getMimicRequests();
1772  double v = position_[joint->getFirstVariableIndex()];
1773  for (std::size_t i = 0; i < mim.size(); ++i)
1774  {
1775  position_[mim[i]->getFirstVariableIndex()] = mim[i]->getMimicFactor() * v + mim[i]->getMimicOffset();
1776  markDirtyJointTransforms(mim[i]);
1777  }
1778  }
1779 
1781  /* use updateMimicJoints() instead, which also marks joints dirty */
1782  MOVEIT_DEPRECATED void updateMimicJoint(const std::vector<const JointModel*>& mim)
1783  {
1784  for (std::size_t i = 0; i < mim.size(); ++i)
1785  {
1786  const int fvi = mim[i]->getFirstVariableIndex();
1787  position_[fvi] =
1788  mim[i]->getMimicFactor() * position_[mim[i]->getMimic()->getFirstVariableIndex()] + mim[i]->getMimicOffset();
1789  // Only mark joint transform dirty, but not the associated link transform
1790  // as this function is always used in combination of
1791  // updateMimicJoint(group->getMimicJointModels()) + markDirtyJointTransforms(group);
1792  dirty_joint_transforms_[mim[i]->getJointIndex()] = 1;
1793  }
1794  }
1795 
1798  {
1799  for (const JointModel* jm : group->getMimicJointModels())
1800  {
1801  const int fvi = jm->getFirstVariableIndex();
1802  position_[fvi] = jm->getMimicFactor() * position_[jm->getMimic()->getFirstVariableIndex()] + jm->getMimicOffset();
1803  markDirtyJointTransforms(jm);
1804  }
1805  markDirtyJointTransforms(group);
1806  }
1807 
1808  void updateLinkTransformsInternal(const JointModel* start);
1809 
1810  void getMissingKeys(const std::map<std::string, double>& variable_map,
1811  std::vector<std::string>& missing_variables) const;
1812  void getStateTreeJointString(std::ostream& ss, const JointModel* jm, const std::string& pfx0, bool last) const;
1813 
1815  bool checkJointTransforms(const JointModel* joint) const;
1816 
1818  bool checkLinkTransforms() const;
1819 
1821  bool checkCollisionTransforms() const;
1822 
1823  RobotModelConstPtr robot_model_;
1824  void* memory_;
1825 
1826  double* position_;
1827  double* velocity_;
1828  double* acceleration_;
1829  double* effort_;
1833 
1836 
1837  Eigen::Affine3d* variable_joint_transforms_; // this points to an element in transforms_, so it is aligned
1838  Eigen::Affine3d* global_link_transforms_; // this points to an element in transforms_, so it is aligned
1839  Eigen::Affine3d* global_collision_body_transforms_; // this points to an element in transforms_, so it is aligned
1840  unsigned char* dirty_joint_transforms_;
1841 
1843  std::map<std::string, AttachedBody*> attached_body_map_;
1844 
1848 
1855 };
1856 
1858 std::ostream& operator<<(std::ostream& out, const RobotState& s);
1859 }
1860 }
1861 
1862 #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:1618
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:527
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:915
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:785
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
Definition: robot_state.h:1671
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:1664
void updateMimicJoint(const JointModel *joint)
Definition: robot_state.h:1769
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:809
Core components of MoveIt!
const Eigen::Affine3d & getGlobalLinkTransform(const LinkModel *link) const
Definition: robot_state.h:1412
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:1724
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:628
Eigen::Affine3d * global_collision_body_transforms_
Definition: robot_state.h:1839
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:830
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:891
ROSCPP_DECL void start()
double distance(const RobotState &other) const
Definition: robot_state.h:1467
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:679
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:901
const Eigen::Affine3d & getJointTransform(const JointModel *joint)
Definition: robot_state.h:1395
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:1797
const Eigen::Affine3d & getGlobalLinkTransform(const std::string &link_name) const
Definition: robot_state.h:1407
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:1368
void enforcePositionBounds(const JointModel *joint)
Definition: robot_state.h:1509
const Eigen::Affine3d & getJointTransform(const std::string &joint_name) const
Definition: robot_state.h:1429
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:1423
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:878
const double * getJointVelocities(const std::string &joint_name) const
Definition: robot_state.h:579
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:1835
const Eigen::Affine3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index) const
Definition: robot_state.h:1418
#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:795
void enforceVelocityBounds(const JointModel *joint)
Definition: robot_state.h:1517
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:1137
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:542
Eigen::Affine3d * global_link_transforms_
Definition: robot_state.h:1838
const double * getJointEffort(const JointModel *joint) const
Definition: robot_state.h:604
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:724
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:703
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:1524
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:1159
void markDirtyJointTransforms(const JointModel *joint)
Definition: robot_state.h:1748
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:666
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:638
void setJointPositions(const std::string &joint_name, const std::vector< double > &position)
Definition: robot_state.h:532
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:1532
bool satisfiesPositionBounds(const JointModel *joint, double margin=0.0) const
Definition: robot_state.h:1528
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:1259
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:599
const Eigen::Affine3d & getJointTransform(const JointModel *joint) const
Definition: robot_state.h:1434
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:744
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:734
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:840
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:1379
void enforceBounds(const JointModel *joint)
Definition: robot_state.h:1503
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:537
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:1474
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:1384
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:757
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:1236
unsigned char * dirty_joint_transforms_
Definition: robot_state.h:1840
bool dirtyLinkTransforms() const
Definition: robot_state.h:1445
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:1360
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:1847
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:863
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:651
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:1705
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:1755
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:1273
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:772
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:1834
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:618
const double * getJointAccelerations(const JointModel *joint) const
Definition: robot_state.h:594
random_numbers::RandomNumberGenerator * rng_
For certain operations a state needs a random number generator. However, it may be slightly expensive...
Definition: robot_state.h:1854
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:554
RobotModelConstPtr robot_model_
Definition: robot_state.h:1823
void setVariableValues(const sensor_msgs::JointState &msg)
Definition: robot_state.h:1292
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:1493
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:584
const Eigen::Affine3d & getJointTransform(const std::string &joint_name)
Definition: robot_state.h:1390
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:1456
bool dirtyJointTransform(const JointModel *joint) const
Definition: robot_state.h:1440
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:850
const double * getJointPositions(const std::string &joint_name) const
Definition: robot_state.h:569
const double * getJointAccelerations(const std::string &joint_name) const
Definition: robot_state.h:589
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:689
const Eigen::Affine3d & getGlobalLinkTransform(const LinkModel *link)
Definition: robot_state.h:1373
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:1837
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:1450
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:574
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:1114
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:1843
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:549
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:1782
void setJointVelocities(const JointModel *joint, const double *velocity)
Definition: robot_state.h:561


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:05