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  if (has_acceleration_)
567  {
568  ROS_ERROR_NAMED("robot_state", "Unable to set joint efforts because array is being used for accelerations");
569  return;
570  }
571  has_effort_ = true;
572 
573  memcpy(effort_ + joint->getFirstVariableIndex(), effort, joint->getVariableCount() * sizeof(double));
574  }
575 
576  const double* getJointPositions(const std::string& joint_name) const
577  {
578  return getJointPositions(robot_model_->getJointModel(joint_name));
579  }
580 
581  const double* getJointPositions(const JointModel* joint) const
582  {
583  return position_ + joint->getFirstVariableIndex();
584  }
585 
586  const double* getJointVelocities(const std::string& joint_name) const
587  {
588  return getJointVelocities(robot_model_->getJointModel(joint_name));
589  }
590 
591  const double* getJointVelocities(const JointModel* joint) const
592  {
593  return velocity_ + joint->getFirstVariableIndex();
594  }
595 
596  const double* getJointAccelerations(const std::string& joint_name) const
597  {
598  return getJointAccelerations(robot_model_->getJointModel(joint_name));
599  }
600 
601  const double* getJointAccelerations(const JointModel* joint) const
602  {
603  return acceleration_ + joint->getFirstVariableIndex();
604  }
605 
606  const double* getJointEffort(const std::string& joint_name) const
607  {
608  return getJointEffort(robot_model_->getJointModel(joint_name));
609  }
610 
611  const double* getJointEffort(const JointModel* joint) const
612  {
613  return effort_ + joint->getFirstVariableIndex();
614  }
615 
625  void setJointGroupPositions(const std::string& joint_group_name, const double* gstate)
626  {
627  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
628  if (jmg)
629  setJointGroupPositions(jmg, gstate);
630  }
631 
635  void setJointGroupPositions(const std::string& joint_group_name, const std::vector<double>& gstate)
636  {
637  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
638  if (jmg)
639  setJointGroupPositions(jmg, &gstate[0]);
640  }
641 
645  void setJointGroupPositions(const JointModelGroup* group, const std::vector<double>& gstate)
646  {
647  setJointGroupPositions(group, &gstate[0]);
648  }
649 
653  void setJointGroupPositions(const JointModelGroup* group, const double* gstate);
654 
658  void setJointGroupPositions(const std::string& joint_group_name, const Eigen::VectorXd& values)
659  {
660  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
661  if (jmg)
662  setJointGroupPositions(jmg, values);
663  }
664 
668  void setJointGroupPositions(const JointModelGroup* group, const Eigen::VectorXd& values);
669 
673  void copyJointGroupPositions(const std::string& joint_group_name, std::vector<double>& gstate) const
674  {
675  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
676  if (jmg)
677  {
678  gstate.resize(jmg->getVariableCount());
679  copyJointGroupPositions(jmg, &gstate[0]);
680  }
681  }
682 
686  void copyJointGroupPositions(const std::string& joint_group_name, double* gstate) const
687  {
688  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
689  if (jmg)
690  copyJointGroupPositions(jmg, gstate);
691  }
692 
696  void copyJointGroupPositions(const JointModelGroup* group, std::vector<double>& gstate) const
697  {
698  gstate.resize(group->getVariableCount());
699  copyJointGroupPositions(group, &gstate[0]);
700  }
701 
705  void copyJointGroupPositions(const JointModelGroup* group, double* gstate) const;
706 
710  void copyJointGroupPositions(const std::string& joint_group_name, Eigen::VectorXd& values) const
711  {
712  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
713  if (jmg)
714  copyJointGroupPositions(jmg, values);
715  }
716 
720  void copyJointGroupPositions(const JointModelGroup* group, Eigen::VectorXd& values) const;
721 
731  void setJointGroupVelocities(const std::string& joint_group_name, const double* gstate)
732  {
733  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
734  if (jmg)
735  setJointGroupVelocities(jmg, gstate);
736  }
737 
741  void setJointGroupVelocities(const std::string& joint_group_name, const std::vector<double>& gstate)
742  {
743  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
744  if (jmg)
745  setJointGroupVelocities(jmg, &gstate[0]);
746  }
747 
751  void setJointGroupVelocities(const JointModelGroup* group, const std::vector<double>& gstate)
752  {
753  setJointGroupVelocities(group, &gstate[0]);
754  }
755 
759  void setJointGroupVelocities(const JointModelGroup* group, const double* gstate);
760 
764  void setJointGroupVelocities(const std::string& joint_group_name, const Eigen::VectorXd& values)
765  {
766  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
767  if (jmg)
768  setJointGroupVelocities(jmg, values);
769  }
770 
774  void setJointGroupVelocities(const JointModelGroup* group, const Eigen::VectorXd& values);
775 
779  void copyJointGroupVelocities(const std::string& joint_group_name, std::vector<double>& gstate) const
780  {
781  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
782  if (jmg)
783  {
784  gstate.resize(jmg->getVariableCount());
785  copyJointGroupVelocities(jmg, &gstate[0]);
786  }
787  }
788 
792  void copyJointGroupVelocities(const std::string& joint_group_name, double* gstate) const
793  {
794  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
795  if (jmg)
796  copyJointGroupVelocities(jmg, gstate);
797  }
798 
802  void copyJointGroupVelocities(const JointModelGroup* group, std::vector<double>& gstate) const
803  {
804  gstate.resize(group->getVariableCount());
805  copyJointGroupVelocities(group, &gstate[0]);
806  }
807 
811  void copyJointGroupVelocities(const JointModelGroup* group, double* gstate) const;
812 
816  void copyJointGroupVelocities(const std::string& joint_group_name, Eigen::VectorXd& values) const
817  {
818  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
819  if (jmg)
820  copyJointGroupVelocities(jmg, values);
821  }
822 
826  void copyJointGroupVelocities(const JointModelGroup* group, Eigen::VectorXd& values) const;
827 
837  void setJointGroupAccelerations(const std::string& joint_group_name, const double* gstate)
838  {
839  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
840  if (jmg)
841  setJointGroupAccelerations(jmg, gstate);
842  }
843 
847  void setJointGroupAccelerations(const std::string& joint_group_name, const std::vector<double>& gstate)
848  {
849  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
850  if (jmg)
851  setJointGroupAccelerations(jmg, &gstate[0]);
852  }
853 
857  void setJointGroupAccelerations(const JointModelGroup* group, const std::vector<double>& gstate)
858  {
859  setJointGroupAccelerations(group, &gstate[0]);
860  }
861 
865  void setJointGroupAccelerations(const JointModelGroup* group, const double* gstate);
866 
870  void setJointGroupAccelerations(const std::string& joint_group_name, const Eigen::VectorXd& values)
871  {
872  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
873  if (jmg)
874  setJointGroupAccelerations(jmg, values);
875  }
876 
880  void setJointGroupAccelerations(const JointModelGroup* group, const Eigen::VectorXd& values);
881 
885  void copyJointGroupAccelerations(const std::string& joint_group_name, std::vector<double>& gstate) const
886  {
887  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
888  if (jmg)
889  {
890  gstate.resize(jmg->getVariableCount());
891  copyJointGroupAccelerations(jmg, &gstate[0]);
892  }
893  }
894 
898  void copyJointGroupAccelerations(const std::string& joint_group_name, double* gstate) const
899  {
900  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
901  if (jmg)
902  copyJointGroupAccelerations(jmg, gstate);
903  }
904 
908  void copyJointGroupAccelerations(const JointModelGroup* group, std::vector<double>& gstate) const
909  {
910  gstate.resize(group->getVariableCount());
911  copyJointGroupAccelerations(group, &gstate[0]);
912  }
913 
917  void copyJointGroupAccelerations(const JointModelGroup* group, double* gstate) const;
918 
922  void copyJointGroupAccelerations(const std::string& joint_group_name, Eigen::VectorXd& values) const
923  {
924  const JointModelGroup* jmg = robot_model_->getJointModelGroup(joint_group_name);
925  if (jmg)
926  copyJointGroupAccelerations(jmg, values);
927  }
928 
932  void copyJointGroupAccelerations(const JointModelGroup* group, Eigen::VectorXd& values) const;
933 
946  bool setToIKSolverFrame(Eigen::Affine3d& pose, const kinematics::KinematicsBaseConstPtr& solver);
947 
954  bool setToIKSolverFrame(Eigen::Affine3d& pose, const std::string& ik_frame);
955 
963  bool setFromIK(const JointModelGroup* group, const geometry_msgs::Pose& pose, unsigned int attempts = 0,
964  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
966 
975  bool setFromIK(const JointModelGroup* group, const geometry_msgs::Pose& pose, const std::string& tip,
976  unsigned int attempts = 0, double timeout = 0.0,
979 
987  bool setFromIK(const JointModelGroup* group, const Eigen::Affine3d& pose, unsigned int attempts = 0,
988  double timeout = 0.0, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn(),
990 
998  bool setFromIK(const JointModelGroup* group, const Eigen::Affine3d& pose, const std::string& tip,
999  unsigned int attempts = 0, double timeout = 0.0,
1002 
1012  bool setFromIK(const JointModelGroup* group, const Eigen::Affine3d& pose, const std::string& tip,
1013  const std::vector<double>& consistency_limits, unsigned int attempts = 0, double timeout = 0.0,
1016 
1027  bool setFromIK(const JointModelGroup* group, const EigenSTL::vector_Affine3d& poses,
1028  const std::vector<std::string>& tips, unsigned int attempts = 0, double timeout = 0.0,
1031 
1043  bool setFromIK(const JointModelGroup* group, const EigenSTL::vector_Affine3d& poses,
1044  const std::vector<std::string>& tips, const std::vector<std::vector<double> >& consistency_limits,
1045  unsigned int attempts = 0, double timeout = 0.0,
1048 
1058  bool setFromIKSubgroups(const JointModelGroup* group, const EigenSTL::vector_Affine3d& poses,
1059  const std::vector<std::string>& tips,
1060  const std::vector<std::vector<double> >& consistency_limits, unsigned int attempts = 0,
1061  double timeout = 0.0,
1064 
1072  bool setFromDiffIK(const JointModelGroup* group, const Eigen::VectorXd& twist, const std::string& tip, double dt,
1074 
1082  bool setFromDiffIK(const JointModelGroup* group, const geometry_msgs::Twist& twist, const std::string& tip, double dt,
1084 
1115  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1116  const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
1117  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
1120 
1121  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1122  const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
1123  double max_step, double jump_threshold_factor,
1126  {
1127  return computeCartesianPath(group, traj, link, direction, global_reference_frame, distance,
1128  MaxEEFStep(max_step, max_step), JumpThreshold(jump_threshold_factor), validCallback,
1129  options);
1130  }
1131 
1138  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1139  const Eigen::Affine3d& target, bool global_reference_frame, const MaxEEFStep& max_step,
1140  const JumpThreshold& jump_threshold,
1143 
1144  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1145  const Eigen::Affine3d& target, bool global_reference_frame, double max_step,
1146  double jump_threshold_factor,
1149  {
1150  return computeCartesianPath(group, traj, link, target, global_reference_frame, MaxEEFStep(max_step),
1151  JumpThreshold(jump_threshold_factor), validCallback, options);
1152  }
1153 
1160  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1161  const EigenSTL::vector_Affine3d& waypoints, bool global_reference_frame,
1162  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
1165 
1166  double computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
1167  const EigenSTL::vector_Affine3d& waypoints, bool global_reference_frame, double max_step,
1168  double jump_threshold_factor,
1171  {
1172  return computeCartesianPath(group, traj, link, waypoints, global_reference_frame, MaxEEFStep(max_step),
1173  JumpThreshold(jump_threshold_factor), validCallback, options);
1174  }
1175 
1191  static double testJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1192  const JumpThreshold& jump_threshold);
1193 
1204  static double testRelativeJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1205  double jump_threshold_factor);
1206 
1219  static double testAbsoluteJointSpaceJump(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
1220  double revolute_jump_threshold, double prismatic_jump_threshold);
1221 
1231  bool getJacobian(const JointModelGroup* group, const LinkModel* link, const Eigen::Vector3d& reference_point_position,
1232  Eigen::MatrixXd& jacobian, bool use_quaternion_representation = false) const;
1233 
1243  bool getJacobian(const JointModelGroup* group, const LinkModel* link, const Eigen::Vector3d& reference_point_position,
1244  Eigen::MatrixXd& jacobian, bool use_quaternion_representation = false)
1245  {
1246  updateLinkTransforms();
1247  return static_cast<const RobotState*>(this)->getJacobian(group, link, reference_point_position, jacobian,
1248  use_quaternion_representation);
1249  }
1250 
1257  Eigen::MatrixXd getJacobian(const JointModelGroup* group,
1258  const Eigen::Vector3d& reference_point_position = Eigen::Vector3d(0.0, 0.0, 0.0)) const;
1259 
1266  Eigen::MatrixXd getJacobian(const JointModelGroup* group,
1267  const Eigen::Vector3d& reference_point_position = Eigen::Vector3d(0.0, 0.0, 0.0))
1268  {
1269  updateLinkTransforms();
1270  return static_cast<const RobotState*>(this)->getJacobian(group, reference_point_position);
1271  }
1272 
1275  void computeVariableVelocity(const JointModelGroup* jmg, Eigen::VectorXd& qdot, const Eigen::VectorXd& twist,
1276  const LinkModel* tip) const;
1277 
1280  void computeVariableVelocity(const JointModelGroup* jmg, Eigen::VectorXd& qdot, const Eigen::VectorXd& twist,
1281  const LinkModel* tip)
1282  {
1283  updateLinkTransforms();
1284  static_cast<const RobotState*>(this)->computeVariableVelocity(jmg, qdot, twist, tip);
1285  }
1286 
1290  bool integrateVariableVelocity(const JointModelGroup* jmg, const Eigen::VectorXd& qdot, double dt,
1292 
1299  void setVariableValues(const sensor_msgs::JointState& msg)
1300  {
1301  if (!msg.position.empty())
1302  setVariablePositions(msg.name, msg.position);
1303  if (!msg.velocity.empty())
1304  setVariableVelocities(msg.name, msg.velocity);
1305  }
1306 
1310  void setToDefaultValues();
1311 
1313  bool setToDefaultValues(const JointModelGroup* group, const std::string& name);
1314 
1316  void setToRandomPositions();
1317 
1319  void setToRandomPositions(const JointModelGroup* group);
1320 
1323  void setToRandomPositions(const JointModelGroup* group, random_numbers::RandomNumberGenerator& rng);
1324 
1330  void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& near, double distance);
1331 
1339  void setToRandomPositionsNearBy(const JointModelGroup* group, const RobotState& near,
1340  const std::vector<double>& distances);
1341 
1350  void updateCollisionBodyTransforms();
1351 
1354  void updateLinkTransforms();
1355 
1357  void update(bool force = false);
1358 
1367  void updateStateWithLinkAt(const std::string& link_name, const Eigen::Affine3d& transform, bool backward = false)
1368  {
1369  updateStateWithLinkAt(robot_model_->getLinkModel(link_name), transform, backward);
1370  }
1371 
1373  void updateStateWithLinkAt(const LinkModel* link, const Eigen::Affine3d& transform, bool backward = false);
1374 
1375  const Eigen::Affine3d& getGlobalLinkTransform(const std::string& link_name)
1376  {
1377  return getGlobalLinkTransform(robot_model_->getLinkModel(link_name));
1378  }
1379 
1380  const Eigen::Affine3d& getGlobalLinkTransform(const LinkModel* link)
1381  {
1382  updateLinkTransforms();
1383  return global_link_transforms_[link->getLinkIndex()];
1384  }
1385 
1386  const Eigen::Affine3d& getCollisionBodyTransforms(const std::string& link_name, std::size_t index)
1387  {
1388  return getCollisionBodyTransform(robot_model_->getLinkModel(link_name), index);
1389  }
1390 
1391  const Eigen::Affine3d& getCollisionBodyTransform(const LinkModel* link, std::size_t index)
1392  {
1393  updateCollisionBodyTransforms();
1394  return global_collision_body_transforms_[link->getFirstCollisionBodyTransformIndex() + index];
1395  }
1396 
1397  const Eigen::Affine3d& getJointTransform(const std::string& joint_name)
1398  {
1399  return getJointTransform(robot_model_->getJointModel(joint_name));
1400  }
1401 
1402  const Eigen::Affine3d& getJointTransform(const JointModel* joint)
1403  {
1404  const int idx = joint->getJointIndex();
1405  unsigned char& dirty = dirty_joint_transforms_[idx];
1406  if (dirty)
1407  {
1408  joint->computeTransform(position_ + joint->getFirstVariableIndex(), variable_joint_transforms_[idx]);
1409  dirty = 0;
1410  }
1411  return variable_joint_transforms_[idx];
1412  }
1413 
1414  const Eigen::Affine3d& getGlobalLinkTransform(const std::string& link_name) const
1415  {
1416  return getGlobalLinkTransform(robot_model_->getLinkModel(link_name));
1417  }
1418 
1419  const Eigen::Affine3d& getGlobalLinkTransform(const LinkModel* link) const
1420  {
1421  BOOST_VERIFY(checkLinkTransforms());
1422  return global_link_transforms_[link->getLinkIndex()];
1423  }
1424 
1425  const Eigen::Affine3d& getCollisionBodyTransform(const std::string& link_name, std::size_t index) const
1426  {
1427  return getCollisionBodyTransform(robot_model_->getLinkModel(link_name), index);
1428  }
1429 
1430  const Eigen::Affine3d& getCollisionBodyTransform(const LinkModel* link, std::size_t index) const
1431  {
1432  BOOST_VERIFY(checkCollisionTransforms());
1433  return global_collision_body_transforms_[link->getFirstCollisionBodyTransformIndex() + index];
1434  }
1435 
1436  const Eigen::Affine3d& getJointTransform(const std::string& joint_name) const
1437  {
1438  return getJointTransform(robot_model_->getJointModel(joint_name));
1439  }
1440 
1441  const Eigen::Affine3d& getJointTransform(const JointModel* joint) const
1442  {
1443  BOOST_VERIFY(checkJointTransforms(joint));
1444  return variable_joint_transforms_[joint->getJointIndex()];
1445  }
1446 
1447  bool dirtyJointTransform(const JointModel* joint) const
1448  {
1449  return dirty_joint_transforms_[joint->getJointIndex()];
1450  }
1451 
1452  bool dirtyLinkTransforms() const
1453  {
1454  return dirty_link_transforms_;
1455  }
1456 
1458  {
1459  return dirty_link_transforms_ || dirty_collision_body_transforms_;
1460  }
1461 
1463  bool dirty() const
1464  {
1465  return dirtyCollisionBodyTransforms();
1466  }
1467 
1474  double distance(const RobotState& other) const
1475  {
1476  return robot_model_->distance(position_, other.getVariablePositions());
1477  }
1478 
1479  double distance(const RobotState& other, const JointModelGroup* joint_group) const;
1480 
1481  double distance(const RobotState& other, const JointModel* joint) const
1482  {
1483  const int idx = joint->getFirstVariableIndex();
1484  return joint->distance(position_ + idx, other.position_ + idx);
1485  }
1486 
1490  void interpolate(const RobotState& to, double t, RobotState& state) const;
1491 
1495  void interpolate(const RobotState& to, double t, RobotState& state, const JointModelGroup* joint_group) const;
1496 
1500  void interpolate(const RobotState& to, double t, RobotState& state, const JointModel* joint) const
1501  {
1502  const int idx = joint->getFirstVariableIndex();
1503  joint->interpolate(position_ + idx, to.position_ + idx, t, state.position_ + idx);
1504  state.markDirtyJointTransforms(joint);
1505  state.updateMimicJoint(joint);
1506  }
1507 
1508  void enforceBounds();
1509  void enforceBounds(const JointModelGroup* joint_group);
1510  void enforceBounds(const JointModel* joint)
1511  {
1512  enforcePositionBounds(joint);
1513  if (has_velocity_)
1514  enforceVelocityBounds(joint);
1515  }
1517  {
1518  if (joint->enforcePositionBounds(position_ + joint->getFirstVariableIndex()))
1519  {
1520  markDirtyJointTransforms(joint);
1521  updateMimicJoint(joint);
1522  }
1523  }
1525  {
1526  joint->enforceVelocityBounds(velocity_ + joint->getFirstVariableIndex());
1527  }
1528 
1529  bool satisfiesBounds(double margin = 0.0) const;
1530  bool satisfiesBounds(const JointModelGroup* joint_group, double margin = 0.0) const;
1531  bool satisfiesBounds(const JointModel* joint, double margin = 0.0) const
1532  {
1533  return satisfiesPositionBounds(joint, margin) && (!has_velocity_ || satisfiesVelocityBounds(joint, margin));
1534  }
1535  bool satisfiesPositionBounds(const JointModel* joint, double margin = 0.0) const
1536  {
1537  return joint->satisfiesPositionBounds(getJointPositions(joint), margin);
1538  }
1539  bool satisfiesVelocityBounds(const JointModel* joint, double margin = 0.0) const
1540  {
1541  return joint->satisfiesVelocityBounds(getJointVelocities(joint), margin);
1542  }
1543 
1546  std::pair<double, const JointModel*> getMinDistanceToPositionBounds() const;
1547 
1550  std::pair<double, const JointModel*> getMinDistanceToPositionBounds(const JointModelGroup* group) const;
1551 
1554  std::pair<double, const JointModel*>
1555  getMinDistanceToPositionBounds(const std::vector<const JointModel*>& joints) const;
1556 
1563  bool isValidVelocityMove(const RobotState& other, const JointModelGroup* group, double dt) const;
1564 
1590  void attachBody(AttachedBody* attached_body);
1591 
1606  void attachBody(const std::string& id, const std::vector<shapes::ShapeConstPtr>& shapes,
1607  const EigenSTL::vector_Affine3d& attach_trans, const std::set<std::string>& touch_links,
1608  const std::string& link_name,
1609  const trajectory_msgs::JointTrajectory& detach_posture = trajectory_msgs::JointTrajectory());
1610 
1625  void attachBody(const std::string& id, const std::vector<shapes::ShapeConstPtr>& shapes,
1626  const EigenSTL::vector_Affine3d& attach_trans, const std::vector<std::string>& touch_links,
1627  const std::string& link_name,
1628  const trajectory_msgs::JointTrajectory& detach_posture = trajectory_msgs::JointTrajectory())
1629  {
1630  std::set<std::string> touch_links_set(touch_links.begin(), touch_links.end());
1631  attachBody(id, shapes, attach_trans, touch_links_set, link_name, detach_posture);
1632  }
1633 
1635  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies) const;
1636 
1638  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const JointModelGroup* lm) const;
1639 
1641  void getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const LinkModel* lm) const;
1642 
1645  bool clearAttachedBody(const std::string& id);
1646 
1648  void clearAttachedBodies(const LinkModel* link);
1649 
1651  void clearAttachedBodies(const JointModelGroup* group);
1652 
1654  void clearAttachedBodies();
1655 
1657  const AttachedBody* getAttachedBody(const std::string& name) const;
1658 
1660  bool hasAttachedBody(const std::string& id) const;
1661 
1662  void setAttachedBodyUpdateCallback(const AttachedBodyCallback& callback);
1667  void computeAABB(std::vector<double>& aabb) const;
1668 
1671  void computeAABB(std::vector<double>& aabb)
1672  {
1673  updateLinkTransforms();
1674  static_cast<const RobotState*>(this)->computeAABB(aabb);
1675  }
1676 
1679  {
1680  if (!rng_)
1682  return *rng_;
1683  }
1684 
1686  const Eigen::Affine3d& getFrameTransform(const std::string& id);
1687 
1689  const Eigen::Affine3d& getFrameTransform(const std::string& id) const;
1690 
1692  bool knowsFrameTransform(const std::string& id) const;
1693 
1701  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1702  const std_msgs::ColorRGBA& color, const std::string& ns, const ros::Duration& dur,
1703  bool include_attached = false) const;
1704 
1712  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1713  const std_msgs::ColorRGBA& color, const std::string& ns, const ros::Duration& dur,
1714  bool include_attached = false)
1715  {
1716  updateCollisionBodyTransforms();
1717  static_cast<const RobotState*>(this)->getRobotMarkers(arr, link_names, color, ns, dur, include_attached);
1718  }
1719 
1724  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1725  bool include_attached = false) const;
1726 
1731  void getRobotMarkers(visualization_msgs::MarkerArray& arr, const std::vector<std::string>& link_names,
1732  bool include_attached = false)
1733  {
1734  updateCollisionBodyTransforms();
1735  static_cast<const RobotState*>(this)->getRobotMarkers(arr, link_names, include_attached);
1736  }
1737 
1738  void printStatePositions(std::ostream& out = std::cout) const;
1739 
1740  void printStateInfo(std::ostream& out = std::cout) const;
1741 
1742  void printTransforms(std::ostream& out = std::cout) const;
1743 
1744  void printTransform(const Eigen::Affine3d& transform, std::ostream& out = std::cout) const;
1745 
1746  void printDirtyInfo(std::ostream& out = std::cout) const;
1747 
1748  std::string getStateTreeString(const std::string& prefix = "") const;
1749 
1750 private:
1751  void allocMemory();
1752 
1753  void copyFrom(const RobotState& other);
1754 
1756  {
1757  dirty_joint_transforms_[joint->getJointIndex()] = 1;
1758  dirty_link_transforms_ =
1759  dirty_link_transforms_ == NULL ? joint : robot_model_->getCommonRoot(dirty_link_transforms_, joint);
1760  }
1761 
1763  {
1764  const std::vector<const JointModel*>& jm = group->getActiveJointModels();
1765  for (std::size_t i = 0; i < jm.size(); ++i)
1766  dirty_joint_transforms_[jm[i]->getJointIndex()] = 1;
1767  dirty_link_transforms_ = dirty_link_transforms_ == NULL ?
1768  group->getCommonRoot() :
1769  robot_model_->getCommonRoot(dirty_link_transforms_, group->getCommonRoot());
1770  }
1771 
1772  void markVelocity();
1773  void markAcceleration();
1774  void markEffort();
1775 
1776  void updateMimicJoint(const JointModel* joint)
1777  {
1778  const std::vector<const JointModel*>& mim = joint->getMimicRequests();
1779  double v = position_[joint->getFirstVariableIndex()];
1780  for (std::size_t i = 0; i < mim.size(); ++i)
1781  {
1782  position_[mim[i]->getFirstVariableIndex()] = mim[i]->getMimicFactor() * v + mim[i]->getMimicOffset();
1783  markDirtyJointTransforms(mim[i]);
1784  }
1785  }
1786 
1788  /* use updateMimicJoints() instead, which also marks joints dirty */
1789  MOVEIT_DEPRECATED void updateMimicJoint(const std::vector<const JointModel*>& mim)
1790  {
1791  for (std::size_t i = 0; i < mim.size(); ++i)
1792  {
1793  const int fvi = mim[i]->getFirstVariableIndex();
1794  position_[fvi] =
1795  mim[i]->getMimicFactor() * position_[mim[i]->getMimic()->getFirstVariableIndex()] + mim[i]->getMimicOffset();
1796  // Only mark joint transform dirty, but not the associated link transform
1797  // as this function is always used in combination of
1798  // updateMimicJoint(group->getMimicJointModels()) + markDirtyJointTransforms(group);
1799  dirty_joint_transforms_[mim[i]->getJointIndex()] = 1;
1800  }
1801  }
1802 
1805  {
1806  for (const JointModel* jm : group->getMimicJointModels())
1807  {
1808  const int fvi = jm->getFirstVariableIndex();
1809  position_[fvi] = jm->getMimicFactor() * position_[jm->getMimic()->getFirstVariableIndex()] + jm->getMimicOffset();
1810  markDirtyJointTransforms(jm);
1811  }
1812  markDirtyJointTransforms(group);
1813  }
1814 
1815  void updateLinkTransformsInternal(const JointModel* start);
1816 
1817  void getMissingKeys(const std::map<std::string, double>& variable_map,
1818  std::vector<std::string>& missing_variables) const;
1819  void getStateTreeJointString(std::ostream& ss, const JointModel* jm, const std::string& pfx0, bool last) const;
1820 
1822  bool checkJointTransforms(const JointModel* joint) const;
1823 
1825  bool checkLinkTransforms() const;
1826 
1828  bool checkCollisionTransforms() const;
1829 
1830  RobotModelConstPtr robot_model_;
1831  void* memory_;
1832 
1833  double* position_;
1834  double* velocity_;
1835  double* acceleration_;
1836  double* effort_;
1840 
1843 
1844  Eigen::Affine3d* variable_joint_transforms_; // this points to an element in transforms_, so it is aligned
1845  Eigen::Affine3d* global_link_transforms_; // this points to an element in transforms_, so it is aligned
1846  Eigen::Affine3d* global_collision_body_transforms_; // this points to an element in transforms_, so it is aligned
1847  unsigned char* dirty_joint_transforms_;
1848 
1850  std::map<std::string, AttachedBody*> attached_body_map_;
1851 
1855 
1862 };
1863 
1865 std::ostream& operator<<(std::ostream& out, const RobotState& s);
1866 }
1867 }
1868 
1869 #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:1625
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:922
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:792
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
Definition: robot_state.h:1678
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:1671
void updateMimicJoint(const JointModel *joint)
Definition: robot_state.h:1776
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:816
Core components of MoveIt!
const Eigen::Affine3d & getGlobalLinkTransform(const LinkModel *link) const
Definition: robot_state.h:1419
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:1731
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:635
Eigen::Affine3d * global_collision_body_transforms_
Definition: robot_state.h:1846
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:837
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:898
ROSCPP_DECL void start()
double distance(const RobotState &other) const
Definition: robot_state.h:1474
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:686
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:908
const Eigen::Affine3d & getJointTransform(const JointModel *joint)
Definition: robot_state.h:1402
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
void setJointEfforts(const JointModel *joint, const double *effort)
Definition: robot_state.h:564
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:1804
const Eigen::Affine3d & getGlobalLinkTransform(const std::string &link_name) const
Definition: robot_state.h:1414
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:1375
void enforcePositionBounds(const JointModel *joint)
Definition: robot_state.h:1516
const Eigen::Affine3d & getJointTransform(const std::string &joint_name) const
Definition: robot_state.h:1436
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:1430
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:885
const double * getJointVelocities(const std::string &joint_name) const
Definition: robot_state.h:586
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:1842
const Eigen::Affine3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index) const
Definition: robot_state.h:1425
#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:802
void enforceVelocityBounds(const JointModel *joint)
Definition: robot_state.h:1524
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:1144
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:1845
const double * getJointEffort(const JointModel *joint) const
Definition: robot_state.h:611
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:731
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:710
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:1531
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:1166
void markDirtyJointTransforms(const JointModel *joint)
Definition: robot_state.h:1755
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:673
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:645
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:1539
bool satisfiesPositionBounds(const JointModel *joint, double margin=0.0) const
Definition: robot_state.h:1535
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:1266
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:606
const Eigen::Affine3d & getJointTransform(const JointModel *joint) const
Definition: robot_state.h:1441
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:751
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:741
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:847
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:1386
void enforceBounds(const JointModel *joint)
Definition: robot_state.h:1510
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:1481
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:1391
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:764
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:1243
unsigned char * dirty_joint_transforms_
Definition: robot_state.h:1847
bool dirtyLinkTransforms() const
Definition: robot_state.h:1452
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:1367
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:1854
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:870
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:658
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:1712
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:1762
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:1280
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:779
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:1841
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:625
const double * getJointAccelerations(const JointModel *joint) const
Definition: robot_state.h:601
random_numbers::RandomNumberGenerator * rng_
For certain operations a state needs a random number generator. However, it may be slightly expensive...
Definition: robot_state.h:1861
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:1830
void setVariableValues(const sensor_msgs::JointState &msg)
Definition: robot_state.h:1299
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
#define ROS_ERROR_NAMED(name,...)
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:1500
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:591
const Eigen::Affine3d & getJointTransform(const std::string &joint_name)
Definition: robot_state.h:1397
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:1463
bool dirtyJointTransform(const JointModel *joint) const
Definition: robot_state.h:1447
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:857
const double * getJointPositions(const std::string &joint_name) const
Definition: robot_state.h:576
const double * getJointAccelerations(const std::string &joint_name) const
Definition: robot_state.h:596
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:696
const Eigen::Affine3d & getGlobalLinkTransform(const LinkModel *link)
Definition: robot_state.h:1380
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:1844
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:1457
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:581
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:1121
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:1850
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:1789
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 Wed Aug 15 2018 10:18:24