openrave.org

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
robot.h
Go to the documentation of this file.
1 // -*- coding: utf-8 -*-
2 // Copyright (C) 2006-2012 Rosen Diankov <rosen.diankov@gmail.com>
3 //
4 // This file is part of OpenRAVE.
5 // OpenRAVE is free software: you can redistribute it and/or modify
6 // it under the terms of the GNU Lesser General Public License as published by
7 // the Free Software Foundation, either version 3 of the License, or
8 // at your option) any later version.
9 //
10 // This program is distributed in the hope that it will be useful,
11 // but WITHOUT ANY WARRANTY; without even the implied warranty of
12 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 // GNU Lesser General Public License for more details.
14 //
15 // You should have received a copy of the GNU Lesser General Public License
16 // along with this program. If not, see <http://www.gnu.org/licenses/>.
22 #ifndef OPENRAVE_ROBOT_H
23 #define OPENRAVE_ROBOT_H
24 
25 namespace OpenRAVE {
26 
31 {
32 public:
37  {
38 public:
39  ManipulatorInfo() : _vdirection(0,0,1) {
40  }
41  virtual ~ManipulatorInfo() {
42  }
43 
44  std::string _name;
45  std::string _sBaseLinkName, _sEffectorLinkName;
47  std::vector<dReal> _vClosingDirection;
49  std::string _sIkSolverXMLId;
50  std::vector<std::string> _vGripperJointNames;
51  };
52  typedef boost::shared_ptr<ManipulatorInfo> ManipulatorInfoPtr;
53  typedef boost::shared_ptr<ManipulatorInfo const> ManipulatorInfoConstPtr;
54 
56  class OPENRAVE_API Manipulator : public boost::enable_shared_from_this<Manipulator>
57  {
58  Manipulator(RobotBasePtr probot, const ManipulatorInfo& info);
59  Manipulator(const Manipulator &r);
60 
62  Manipulator(RobotBasePtr probot, boost::shared_ptr<Manipulator const> r);
63 
64 public:
65  virtual ~Manipulator();
66 
68  inline const ManipulatorInfo& GetInfo() const {
69  return _info;
70  }
71 
76  virtual Transform GetTransform() const;
77 
79  virtual std::pair<Vector,Vector> GetVelocity() const;
80 
82  return GetTransform();
83  }
84 
85  virtual const std::string& GetName() const {
86  return _info._name;
87  }
88  virtual RobotBasePtr GetRobot() const {
89  return RobotBasePtr(__probot);
90  }
91 
97  virtual bool SetIkSolver(IkSolverBasePtr iksolver);
98 
100  virtual IkSolverBasePtr GetIkSolver() const;
101 
103  virtual LinkPtr GetBase() const {
104  return __pBase;
105  }
106 
108  virtual LinkPtr GetEndEffector() const {
109  return __pEffector;
110  }
111 
114  return _info._tLocalTool;
115  }
116 
120  virtual void SetLocalToolTransform(const Transform& t);
121 
125  virtual void SetName(const std::string& name);
126 
129  return GetLocalToolTransform();
130  }
131 
133  virtual const std::vector<int>& GetGripperIndices() const {
134  return __vgripperdofindices;
135  }
136 
140  virtual const std::vector<int>& GetArmIndices() const {
141  return __varmdofindices;
142  }
143 
145  virtual const std::vector<dReal>& GetClosingDirection() const {
146  return _info._vClosingDirection;
147  }
148 
152  virtual void SetLocalToolDirection(const Vector& direction);
153 
155  virtual Vector GetLocalToolDirection() const {
156  return _info._vdirection;
157  }
158 
160  virtual Vector GetDirection() const {
161  return GetLocalToolDirection();
162  }
163 
172  virtual bool FindIKSolution(const IkParameterization& param, std::vector<dReal>& solution, int filteroptions) const;
173  virtual bool FindIKSolution(const IkParameterization& param, const std::vector<dReal>& vFreeParameters, std::vector<dReal>& solution, int filteroptions) const;
174  virtual bool FindIKSolution(const IkParameterization& param, int filteroptions, IkReturnPtr ikreturn) const;
175  virtual bool FindIKSolution(const IkParameterization& param, const std::vector<dReal>& vFreeParameters, int filteroptions, IkReturnPtr ikreturn) const;
176 
182  virtual bool FindIKSolutions(const IkParameterization& param, std::vector<std::vector<dReal> >& solutions, int filteroptions) const;
183  virtual bool FindIKSolutions(const IkParameterization& param, const std::vector<dReal>& vFreeParameters, std::vector<std::vector<dReal> >& solutions, int filteroptions) const;
184  virtual bool FindIKSolutions(const IkParameterization& param, int filteroptions, std::vector<IkReturnPtr>& vikreturns) const;
185  virtual bool FindIKSolutions(const IkParameterization& param, const std::vector<dReal>& vFreeParameters, int filteroptions, std::vector<IkReturnPtr>& vikreturns) const;
186 
204  virtual IkParameterization GetIkParameterization(IkParameterizationType iktype, bool inworld=true) const;
205 
214  virtual IkParameterization GetIkParameterization(const IkParameterization& ikparam, bool inworld=true) const;
215 
217  virtual void GetChildJoints(std::vector<JointPtr>& vjoints) const;
218 
220  virtual void GetChildDOFIndices(std::vector<int>& vdofndices) const;
221 
225  virtual bool IsChildLink(LinkConstPtr plink) const;
226 
230  virtual void GetChildLinks(std::vector<LinkPtr>& vlinks) const;
231 
236  virtual void GetIndependentLinks(std::vector<LinkPtr>& vlinks) const;
237 
244  virtual bool CheckEndEffectorCollision(const Transform& tEE, CollisionReportPtr report = CollisionReportPtr()) const;
245 
252  virtual bool CheckEndEffectorSelfCollision(const Transform& tEE, CollisionReportPtr report = CollisionReportPtr()) const;
253 
261 
262  virtual bool CheckEndEffectorCollision(const IkParameterization& ikparam, CollisionReportPtr report = CollisionReportPtr()) const;
263 
271 
272  virtual bool CheckEndEffectorSelfCollision(const IkParameterization& ikparam, CollisionReportPtr report = CollisionReportPtr()) const;
273 
279  virtual bool CheckIndependentCollision(CollisionReportPtr report = CollisionReportPtr()) const;
280 
287  //virtual bool CheckIndependentCollision(KinBodyConstPtr body, CollisionReportPtr report = CollisionReportPtr()) const;
288 
290  virtual bool IsGrabbing(KinBodyConstPtr body) const;
291 
295  virtual void CalculateJacobian(std::vector<dReal>& jacobian) const;
296 
298  virtual void CalculateJacobian(boost::multi_array<dReal,2>& jacobian) const;
299 
301  virtual void CalculateRotationJacobian(std::vector<dReal>& jacobian) const;
302 
304  virtual void CalculateRotationJacobian(boost::multi_array<dReal,2>& jacobian) const;
305 
307  virtual void CalculateAngularVelocityJacobian(std::vector<dReal>& jacobian) const;
308 
310  virtual void CalculateAngularVelocityJacobian(boost::multi_array<dReal,2>& jacobian) const;
311 
315  virtual ConfigurationSpecification GetArmConfigurationSpecification(const std::string& interpolation="") const;
316 
317  virtual void serialize(std::ostream& o, int options) const;
318 
320  virtual const std::string& GetStructureHash() const;
321 
325  virtual const std::string& GetKinematicsStructureHash() const;
326 protected:
328  virtual void _ComputeInternalInformation();
329 
331 private:
332  RobotBaseWeakPtr __probot;
333  LinkPtr __pBase, __pEffector;
334  std::vector<int> __vgripperdofindices, __varmdofindices;
335  ConfigurationSpecification __armspec;
336  mutable IkSolverBasePtr __pIkSolver;
337  mutable std::string __hashstructure, __hashkinematicsstructure;
338 
339 #ifdef RAVE_PRIVATE
340 #ifdef _MSC_VER
341  friend class OpenRAVEXMLParser::ManipulatorXMLReader;
342  friend class OpenRAVEXMLParser::RobotXMLReader;
343  friend class XFileReader;
344 #else
345  friend class ::OpenRAVEXMLParser::ManipulatorXMLReader;
346  friend class ::OpenRAVEXMLParser::RobotXMLReader;
347  friend class ::XFileReader;
348 #endif
349 #endif
350  friend class ColladaReader;
351  friend class RobotBase;
352  };
353  typedef boost::shared_ptr<RobotBase::Manipulator> ManipulatorPtr;
354  typedef boost::shared_ptr<RobotBase::Manipulator const> ManipulatorConstPtr;
355  typedef boost::weak_ptr<RobotBase::Manipulator> ManipulatorWeakPtr;
356 
361  {
362 public:
364  }
366  }
367 
368  std::string _name;
369  std::string _linkname;
371  std::string _sensorname;
373  };
374  typedef boost::shared_ptr<AttachedSensorInfo> AttachedSensorInfoPtr;
375  typedef boost::shared_ptr<AttachedSensorInfo const> AttachedSensorInfoConstPtr;
376 
378  class OPENRAVE_API AttachedSensor : public boost::enable_shared_from_this<AttachedSensor>
379  {
380 public:
382  AttachedSensor(RobotBasePtr probot, const AttachedSensor &sensor, int cloningoptions);
383  virtual ~AttachedSensor();
384 
385  virtual SensorBasePtr GetSensor() const {
386  return psensor;
387  }
388  virtual LinkPtr GetAttachingLink() const {
389  return LinkPtr(pattachedlink);
390  }
391  virtual Transform GetRelativeTransform() const {
392  return trelative;
393  }
394  virtual Transform GetTransform() const {
395  return LinkPtr(pattachedlink)->GetTransform()*trelative;
396  }
397  virtual RobotBasePtr GetRobot() const {
398  return RobotBasePtr(_probot);
399  }
400  virtual const std::string& GetName() const {
401  return _name;
402  }
403 
405  virtual SensorBase::SensorDataPtr GetData() const;
406 
407  virtual void SetRelativeTransform(const Transform& t);
408 
409  virtual void serialize(std::ostream& o, int options) const;
410 
412  virtual const std::string& GetStructureHash() const;
413 private:
414  RobotBaseWeakPtr _probot;
415  SensorBasePtr psensor;
416  LinkWeakPtr pattachedlink;
417  Transform trelative;
419  std::string _name;
420  mutable std::string __hashstructure;
421 #ifdef RAVE_PRIVATE
422 #ifdef _MSC_VER
423  friend class OpenRAVEXMLParser::AttachedSensorXMLReader;
424  friend class OpenRAVEXMLParser::RobotXMLReader;
425  friend class XFileReader;
426 #else
427  friend class ::OpenRAVEXMLParser::AttachedSensorXMLReader;
428  friend class ::OpenRAVEXMLParser::RobotXMLReader;
429  friend class ::XFileReader;
430 #endif
431 #endif
432  friend class ColladaReader;
433  friend class RobotBase;
434  };
435  typedef boost::shared_ptr<RobotBase::AttachedSensor> AttachedSensorPtr;
436  typedef boost::shared_ptr<RobotBase::AttachedSensor const> AttachedSensorConstPtr;
437 
442  {
443 public:
444  std::string _grabbedname;
445  std::string _robotlinkname;
447  std::set<int> _setRobotLinksToIgnore;
448  };
449  typedef boost::shared_ptr<GrabbedInfo> GrabbedInfoPtr;
450  typedef boost::shared_ptr<GrabbedInfo const> GrabbedInfoConstPtr;
451 
453  class OPENRAVE_API RobotStateSaver : public KinBodyStateSaver
454  {
455 public:
456  RobotStateSaver(RobotBasePtr probot, int options = Save_LinkTransformation|Save_LinkEnable|Save_ActiveDOF|Save_ActiveManipulator);
457  virtual ~RobotStateSaver();
458 
463  virtual void Restore(boost::shared_ptr<RobotBase> robot=boost::shared_ptr<RobotBase>());
464 
468  virtual void Release();
469 
470 protected:
472  std::vector<int> vactivedofs;
476  std::vector<UserDataPtr> _vGrabbedBodies;
477 private:
478  virtual void _RestoreRobot(boost::shared_ptr<RobotBase> robot);
479  };
480 
481  typedef boost::shared_ptr<RobotStateSaver> RobotStateSaverPtr;
482 
483  virtual ~RobotBase();
484 
486  static inline InterfaceType GetInterfaceTypeStatic() {
487  return PT_Robot;
488  }
489 
490  virtual void Destroy();
491 
497  virtual bool Init(const std::vector<LinkInfoConstPtr>& linkinfos, const std::vector<JointInfoConstPtr>& jointinfos, const std::vector<ManipulatorInfoConstPtr>& manipinfos, const std::vector<AttachedSensorInfoConstPtr>& attachedsensorinfos);
498 
499 
501  virtual std::vector<ManipulatorPtr>& GetManipulators() {
502  return _vecManipulators;
503  }
504 
505  virtual std::vector<AttachedSensorPtr>& GetAttachedSensors() {
506  return _vecSensors;
507  }
508 
509  virtual void SetName(const std::string& name);
510 
511  virtual void SetDOFValues(const std::vector<dReal>& vJointValues, uint32_t checklimits = 1, const std::vector<int>& dofindices = std::vector<int>());
512  virtual void SetDOFValues(const std::vector<dReal>& vJointValues, const Transform& transbase, uint32_t checklimits = 1);
513 
514  virtual void SetLinkTransformations(const std::vector<Transform>& transforms);
515  virtual void SetLinkTransformations(const std::vector<Transform>& transforms, const std::vector<int>& dofbranches);
516 
517  virtual bool SetVelocity(const Vector& linearvel, const Vector& angularvel);
518  virtual void SetDOFVelocities(const std::vector<dReal>& dofvelocities, const Vector& linearvel, const Vector& angularvel,uint32_t checklimits = 1);
519  virtual void SetDOFVelocities(const std::vector<dReal>& dofvelocities, uint32_t checklimits = 1, const std::vector<int>& dofindices = std::vector<int>());
520 
523  virtual void SetTransform(const Transform& trans);
524 
537 
545 
551  virtual void SetActiveDOFs(const std::vector<int>& dofindices, int affine = OpenRAVE::DOF_NoTransform);
552 
559  virtual void SetActiveDOFs(const std::vector<int>& dofindices, int affine, const Vector& rotationaxis);
560  virtual int GetActiveDOF() const {
561  return _nActiveDOF >= 0 ? _nActiveDOF : GetDOF();
562  }
563  virtual int GetAffineDOF() const {
564  return _nAffineDOFs;
565  }
566 
568  virtual int GetAffineDOFIndex(DOFAffine dof) const {
569  return GetActiveDOFIndices().size()+RaveGetIndexFromAffineDOF(GetAffineDOF(),dof);
570  }
571 
575  virtual ConfigurationSpecification GetActiveConfigurationSpecification(const std::string& interpolation="") const;
576 
578  virtual const std::vector<int>& GetActiveDOFIndices() const;
579 
580  virtual Vector GetAffineRotationAxis() const {
581  return vActvAffineRotationAxis;
582  }
583  virtual void SetAffineTranslationLimits(const Vector& lower, const Vector& upper);
584  virtual void SetAffineRotationAxisLimits(const Vector& lower, const Vector& upper);
585  virtual void SetAffineRotation3DLimits(const Vector& lower, const Vector& upper);
586 
591  virtual void SetAffineRotationQuatLimits(const Vector& quatangle);
592  virtual void SetAffineTranslationMaxVels(const Vector& vels);
593  virtual void SetAffineRotationAxisMaxVels(const Vector& vels);
594  virtual void SetAffineRotation3DMaxVels(const Vector& vels);
595  virtual void SetAffineRotationQuatMaxVels(dReal vels);
596  virtual void SetAffineTranslationResolution(const Vector& resolution);
597  virtual void SetAffineRotationAxisResolution(const Vector& resolution);
598  virtual void SetAffineRotation3DResolution(const Vector& resolution);
599  virtual void SetAffineRotationQuatResolution(dReal resolution);
600  virtual void SetAffineTranslationWeights(const Vector& weights);
601  virtual void SetAffineRotationAxisWeights(const Vector& weights);
602  virtual void SetAffineRotation3DWeights(const Vector& weights);
603  virtual void SetAffineRotationQuatWeights(dReal weights);
604 
605  virtual void GetAffineTranslationLimits(Vector& lower, Vector& upper) const;
606  virtual void GetAffineRotationAxisLimits(Vector& lower, Vector& upper) const;
607  virtual void GetAffineRotation3DLimits(Vector& lower, Vector& upper) const;
608 
613  return _vRotationQuatLimitStart * _fQuatLimitMaxAngle;
614  }
616  return _vTranslationMaxVels;
617  }
619  return _vRotationAxisMaxVels;
620  }
622  return _vRotation3DMaxVels;
623  }
625  return _fQuatMaxAngleVelocity;
626  }
628  return _vTranslationResolutions;
629  }
631  return _vRotationAxisResolutions;
632  }
634  return _vRotation3DResolutions;
635  }
637  return _fQuatAngleResolution;
638  }
640  return _vTranslationWeights;
641  }
643  return _vRotationAxisWeights;
644  }
646  return _vRotation3DWeights;
647  }
649  return _fQuatAngleResolution;
650  }
651 
652  virtual void SetActiveDOFValues(const std::vector<dReal>& values, uint32_t checklimits=1);
653  virtual void GetActiveDOFValues(std::vector<dReal>& v) const;
654  virtual void SetActiveDOFVelocities(const std::vector<dReal>& velocities, uint32_t checklimits=1);
655  virtual void GetActiveDOFVelocities(std::vector<dReal>& velocities) const;
656  virtual void GetActiveDOFLimits(std::vector<dReal>& lower, std::vector<dReal>& upper) const;
657  virtual void GetActiveDOFResolutions(std::vector<dReal>& v) const;
658  virtual void GetActiveDOFWeights(std::vector<dReal>& v) const;
659  virtual void GetActiveDOFVelocityLimits(std::vector<dReal>& v) const;
660  virtual void GetActiveDOFAccelerationLimits(std::vector<dReal>& v) const;
661  virtual void GetActiveDOFMaxVel(std::vector<dReal>& v) const {
662  return GetActiveDOFVelocityLimits(v);
663  }
664  virtual void GetActiveDOFMaxAccel(std::vector<dReal>& v) const {
665  return GetActiveDOFAccelerationLimits(v);
666  }
667 
669  virtual void SubtractActiveDOFValues(std::vector<dReal>& q1, const std::vector<dReal>& q2) const;
670 
672  virtual void SetActiveManipulator(int index) RAVE_DEPRECATED;
673 
678  virtual ManipulatorPtr SetActiveManipulator(const std::string& manipname);
679  virtual void SetActiveManipulator(ManipulatorConstPtr pmanip);
680  virtual ManipulatorPtr GetActiveManipulator();
681  virtual ManipulatorConstPtr GetActiveManipulator() const;
682 
689  virtual ManipulatorPtr AddManipulator(const ManipulatorInfo& manipinfo);
690 
695  virtual void RemoveManipulator(ManipulatorPtr manip);
696 
698  virtual int GetActiveManipulatorIndex() const RAVE_DEPRECATED;
699 
701  virtual bool SetMotion(TrajectoryBaseConstPtr ptraj) RAVE_DEPRECATED;
702 
704  virtual bool SetActiveMotion(TrajectoryBaseConstPtr ptraj) RAVE_DEPRECATED;
705 
707  virtual bool SetActiveMotion(TrajectoryBaseConstPtr ptraj, dReal fSpeed) RAVE_DEPRECATED;
708 
709 
716  virtual void CalculateActiveJacobian(int index, const Vector& offset, std::vector<dReal>& jacobian) const;
717  virtual void CalculateActiveJacobian(int index, const Vector& offset, boost::multi_array<dReal,2>& jacobian) const;
718 
719  virtual void CalculateActiveRotationJacobian(int index, const Vector& qInitialRot, std::vector<dReal>& jacobian) const;
720  virtual void CalculateActiveRotationJacobian(int index, const Vector& qInitialRot, boost::multi_array<dReal,2>& jacobian) const;
721 
722 
728  virtual void CalculateActiveAngularVelocityJacobian(int index, std::vector<dReal>& jacobian) const;
729  virtual void CalculateActiveAngularVelocityJacobian(int index, boost::multi_array<dReal,2>& jacobian) const;
730 
731  virtual const std::set<int>& GetNonAdjacentLinks(int adjacentoptions=0) const;
732 
734 
752  virtual bool Grab(KinBodyPtr body, LinkPtr pRobotLinkToGrabWith, const std::set<int>& setRobotLinksToIgnore);
753 
760  virtual bool Grab(KinBodyPtr body, LinkPtr pRobotLinkToGrabWith);
761 
769  virtual bool Grab(KinBodyPtr body, const std::set<int>& setRobotLinksToIgnore);
770 
776  virtual bool Grab(KinBodyPtr body);
777 
782  virtual void Release(KinBodyPtr body);
783 
785  virtual void ReleaseAllGrabbed();
786 
791  virtual void RegrabAll();
792 
797  virtual LinkPtr IsGrabbing(KinBodyConstPtr body) const;
798 
803  virtual void GetGrabbed(std::vector<KinBodyPtr>& vbodies) const;
804 
809  virtual void GetGrabbedInfo(std::vector<GrabbedInfoPtr>& vgrabbedinfo) const;
810 
816  virtual void ResetGrabbed(const std::vector<GrabbedInfoConstPtr>& vgrabbedinfo);
817 
823  virtual void GetIgnoredLinksOfGrabbed(KinBodyConstPtr body, std::list<KinBody::LinkConstPtr>& ignorelinks) const;
824 
826 
831  virtual void SimulationStep(dReal fElapsedTime);
832 
837  virtual bool CheckSelfCollision(CollisionReportPtr report = CollisionReportPtr()) const;
838 
845  virtual bool CheckLinkCollision(int ilinkindex, const Transform& tlinktrans, CollisionReportPtr report = CollisionReportPtr());
846 
853  virtual bool CheckLinkSelfCollision(int ilinkindex, const Transform& tlinktrans, CollisionReportPtr report = CollisionReportPtr());
854 
856  virtual void Clone(InterfaceBaseConstPtr preference, int cloningoptions);
857 
859  virtual bool IsRobot() const {
860  return true;
861  }
862 
863  virtual void serialize(std::ostream& o, int options) const;
864 
867  virtual const std::string& GetRobotStructureHash() const;
868 
871  return ControllerBasePtr();
872  }
873 
877  virtual bool SetController(ControllerBasePtr controller, const std::vector<int>& dofindices, int nControlTransformation);
878 
880  void GetFullTrajectoryFromActive(TrajectoryBasePtr pfulltraj, TrajectoryBaseConstPtr pActiveTraj, bool bOverwriteTransforms=true) RAVE_DEPRECATED;
881 
882 protected:
884 
885  inline RobotBasePtr shared_robot() {
886  return boost::static_pointer_cast<RobotBase>(shared_from_this());
887  }
889  return boost::static_pointer_cast<RobotBase const>(shared_from_this());
890  }
891 
893  virtual void _Regrab(UserDataPtr pgrabbed);
894 
896  virtual void _ComputeInternalInformation();
897 
901  virtual void _ParametersChanged(int parameters);
902 
903  std::vector<UserDataPtr> _vGrabbedBodies;
904  virtual void _UpdateGrabbedBodies();
905  virtual void _UpdateAttachedSensors();
906  std::vector<ManipulatorPtr> _vecManipulators;
908 
909  std::vector<AttachedSensorPtr> _vecSensors;
910 
911  std::vector<int> _vActiveDOFIndices, _vAllDOFIndices;
915 
916  Vector _vTranslationLowerLimits, _vTranslationUpperLimits, _vTranslationMaxVels, _vTranslationResolutions, _vTranslationWeights;
918  Vector _vRotationAxisLowerLimits, _vRotationAxisUpperLimits, _vRotationAxisMaxVels, _vRotationAxisResolutions, _vRotationAxisWeights;
919  Vector _vRotation3DLowerLimits, _vRotation3DUpperLimits, _vRotation3DMaxVels, _vRotation3DResolutions, _vRotation3DWeights;
921  dReal _fQuatLimitMaxAngle, _fQuatMaxAngleVelocity, _fQuatAngleResolution, _fQuatAngleWeight;
922 
924 private:
925  virtual const char* GetHash() const {
926  return OPENRAVE_ROBOT_HASH;
927  }
928  virtual const char* GetKinBodyHash() const {
929  return OPENRAVE_KINBODY_HASH;
930  }
931  mutable std::string __hashrobotstructure;
932  mutable std::vector<dReal> _vTempRobotJoints;
933 
934 #ifdef RAVE_PRIVATE
935 #ifdef _MSC_VER
936  friend class Environment;
937  friend class OpenRAVEXMLParser::RobotXMLReader;
938  friend class OpenRAVEXMLParser::ManipulatorXMLReader;
939  friend class OpenRAVEXMLParser::AttachedSensorXMLReader;
940  friend class XFileReader;
941 #else
942  friend class ::Environment;
943  friend class ::OpenRAVEXMLParser::RobotXMLReader;
944  friend class ::OpenRAVEXMLParser::ManipulatorXMLReader;
945  friend class ::OpenRAVEXMLParser::AttachedSensorXMLReader;
946  friend class ::XFileReader;
947 #endif
948 #endif
949  friend class ColladaWriter;
950  friend class ColladaReader;
951  friend class RaveDatabase;
952  friend class Grabbed;
953 };
954 
955 } // end namespace OpenRAVE
956 
957 #endif // ROBOT_H