collisionchecker.h   collisionchecker.h 
skipping to change at line 96 skipping to change at line 96
/// \brief return the static interface type this class points to (used for safe casting) /// \brief return the static interface type this class points to (used for safe casting)
static inline InterfaceType GetInterfaceTypeStatic() { return PT_Collis ionChecker; } static inline InterfaceType GetInterfaceTypeStatic() { return PT_Collis ionChecker; }
/// \brief Set basic collision options using the CollisionOptions enum /// \brief Set basic collision options using the CollisionOptions enum
virtual bool SetCollisionOptions(int collisionoptions) = 0; virtual bool SetCollisionOptions(int collisionoptions) = 0;
/// \brief get the current collision options /// \brief get the current collision options
virtual int GetCollisionOptions() const = 0; virtual int GetCollisionOptions() const = 0;
/// \deprecated (10/11/18) use SendCommand instead
virtual bool SetCollisionOptions(std::ostream& sout, std::istream& sinp
ut) RAVE_DEPRECATED { throw openrave_exception("SetCollisionsOptions not su
pported",ORE_NotImplemented); }
virtual void SetTolerance(dReal tolerance) = 0; virtual void SetTolerance(dReal tolerance) = 0;
/// notified when a new body has been initialized in the environment /// notified when a new body has been initialized in the environment
virtual bool InitKinBody(KinBodyPtr pbody) = 0; virtual bool InitKinBody(KinBodyPtr pbody) = 0;
/// \deprecated (10/12/03) use \see EnableLink /// \deprecated (10/12/03) use \see EnableLink
virtual bool Enable(KinBodyConstPtr pbody, bool bEnable) RAVE_DEPRECATE D = 0; virtual bool Enable(KinBodyConstPtr pbody, bool bEnable) RAVE_DEPRECATE D = 0;
/// enables or disables a link from being considered in collisions /// enables or disables a link from being considered in collisions
/// \return true if operation succeeded /// \return true if operation succeeded
 End of changes. 1 change blocks. 
5 lines changed or deleted 0 lines changed or added


 config.h   config.h 
/** \file config.h /** \file config.h
\brief Defines OpenRAVE installation-specific information. \brief Defines OpenRAVE installation-specific information.
*/ */
#ifndef OPENRAVE_DEFINITIONS_H #ifndef OPENRAVE_DEFINITIONS_H
#define OPENRAVE_DEFINITIONS_H #define OPENRAVE_DEFINITIONS_H
#if defined(_WIN32) || defined(__CYGWIN__) || defined(_MSC_VER)
#define OPENRAVE_HELPER_DLL_IMPORT __declspec(dllimport)
#define OPENRAVE_HELPER_DLL_EXPORT __declspec(dllexport)
#define OPENRAVE_HELPER_DLL_LOCAL
#else
#if __GNUC__ >= 4
#define OPENRAVE_HELPER_DLL_IMPORT __attribute__ ((visibility("default"
)))
#define OPENRAVE_HELPER_DLL_EXPORT __attribute__ ((visibility("default"
)))
#define OPENRAVE_HELPER_DLL_LOCAL __attribute__ ((visibility("hidden")
))
#else
#define OPENRAVE_HELPER_DLL_IMPORT
#define OPENRAVE_HELPER_DLL_EXPORT
#define OPENRAVE_HELPER_DLL_LOCAL
#endif
#endif
// Now we use the generic helper definitions above to define OPENRAVE_API a
nd OPENRAVE_LOCAL.
// OPENRAVE_API is used for the public API symbols. It either DLL imports o
r DLL exports (or does nothing for static build)
// OPENRAVE_LOCAL is used for non-api symbols.
#if defined(OPENRAVE_DLL) || defined(OPENRAVE_CORE_DLL) // defined if OpenR
AVE is compiled as a DLL
#ifdef OPENRAVE_DLL_EXPORTS // defined if we are building the OpenRAVE DL
L (instead of using it)
#define OPENRAVE_API OPENRAVE_HELPER_DLL_EXPORT
#else
#define OPENRAVE_API OPENRAVE_HELPER_DLL_IMPORT
#endif // OPENRAVE_DLL_EXPORTS
#define OPENRAVE_LOCAL OPENRAVE_HELPER_DLL_LOCAL
#else // OPENRAVE_DLL is not defined: this means OpenRAVE is a static lib.
#define OPENRAVE_API
#define OPENRAVE_LOCAL
#endif // OPENRAVE_DLL
#define OPENRAVE_VERSION_MAJOR 0 #define OPENRAVE_VERSION_MAJOR 0
#define OPENRAVE_VERSION_MINOR 3 #define OPENRAVE_VERSION_MINOR 4
#define OPENRAVE_VERSION_PATCH 2 #define OPENRAVE_VERSION_PATCH 0
#define OPENRAVE_VERSION_COMBINED(major, minor, patch) (((major) << 16) | ( (minor) << 8) | (patch)) #define OPENRAVE_VERSION_COMBINED(major, minor, patch) (((major) << 16) | ( (minor) << 8) | (patch))
#define OPENRAVE_VERSION OPENRAVE_VERSION_COMBINED(OPENRAVE_VERSION_MAJOR, OPENRAVE_VERSION_MINOR, OPENRAVE_VERSION_PATCH) #define OPENRAVE_VERSION OPENRAVE_VERSION_COMBINED(OPENRAVE_VERSION_MAJOR, OPENRAVE_VERSION_MINOR, OPENRAVE_VERSION_PATCH)
#define OPENRAVE_VERSION_EXTRACT_MAJOR(version) (((version)>>16)&0xff) #define OPENRAVE_VERSION_EXTRACT_MAJOR(version) (((version)>>16)&0xff)
#define OPENRAVE_VERSION_EXTRACT_MINOR(version) (((version)>>8)&0xff) #define OPENRAVE_VERSION_EXTRACT_MINOR(version) (((version)>>8)&0xff)
#define OPENRAVE_VERSION_EXTRACT_PATCH(version) (((version))&0xff) #define OPENRAVE_VERSION_EXTRACT_PATCH(version) (((version))&0xff)
#define OPENRAVE_VERSION_STRING "0.3.2" #define OPENRAVE_VERSION_STRING "0.4.0"
#define OPENRAVE_VERSION_STRING_FORMAT(version) boost::str(boost::format("% s.%s.%s")%(OPENRAVE_VERSION_EXTRACT_MAJOR(version))%(OPENRAVE_VERSION_EXTRA CT_MINOR(version))%(OPENRAVE_VERSION_EXTRACT_PATCH(version))) #define OPENRAVE_VERSION_STRING_FORMAT(version) boost::str(boost::format("% s.%s.%s")%(OPENRAVE_VERSION_EXTRACT_MAJOR(version))%(OPENRAVE_VERSION_EXTRA CT_MINOR(version))%(OPENRAVE_VERSION_EXTRACT_PATCH(version)))
#define OPENRAVE_VERSION_GE(major1, minor1, patch1, major2, minor2, patch2) (OPENRAVE_VERSION_COMBINED(major1, minor1, patch1) >= OPENRAVE_VERSION_COM BINED(major2, minor2, patch2)) #define OPENRAVE_VERSION_GE(major1, minor1, patch1, major2, minor2, patch2) (OPENRAVE_VERSION_COMBINED(major1, minor1, patch1) >= OPENRAVE_VERSION_COM BINED(major2, minor2, patch2))
#define OPENRAVE_VERSION_MINIMUM(major, minor, patch) OPENRAVE_VERSION_GE(O PENRAVE_VERSION_MAJOR, OPENRAVE_VERSION_MINOR, OPENRAVE_VERSION_PATCH, majo r, minor, patch) #define OPENRAVE_VERSION_MINIMUM(major, minor, patch) OPENRAVE_VERSION_GE(O PENRAVE_VERSION_MAJOR, OPENRAVE_VERSION_MINOR, OPENRAVE_VERSION_PATCH, majo r, minor, patch)
// if 0, single precision // if 0, single precision
// if 1, double precision // if 1, double precision
#define OPENRAVE_PRECISION 1 #define OPENRAVE_PRECISION 1
#define OPENRAVE_PLUGINS_INSTALL_DIR "/home/andrey/upstream-tracker/testing #define OPENRAVE_PLUGINS_INSTALL_DIR "/home/andrey/upstream-tracker/testing
/openrave/0.3.2/share/openrave-0.3/plugins" /openrave/0.4.0/share/openrave-0.4/plugins"
#define OPENRAVE_DATA_INSTALL_DIR "/home/andrey/upstream-tracker/testing/op #define OPENRAVE_DATA_INSTALL_DIR "/home/andrey/upstream-tracker/testing/op
enrave/0.3.2/share/openrave-0.3" enrave/0.4.0/share/openrave-0.4"
#define OPENRAVE_PYTHON_INSTALL_DIR "/home/andrey/upstream-tracker/testing/ #define OPENRAVE_PYTHON_INSTALL_DIR "/home/andrey/upstream-tracker/testing/
openrave/0.3.2/lib/python2.7/site-packages" openrave/0.4.0/lib/python2.7/site-packages"
#endif #endif
 End of changes. 4 change blocks. 
9 lines changed or deleted 47 lines changed or added


 controller.h   controller.h 
skipping to change at line 25 skipping to change at line 25
// You should have received a copy of the GNU Lesser General Public License // You should have received a copy of the GNU Lesser General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>. // along with this program. If not, see <http://www.gnu.org/licenses/>.
/** \file controller.h /** \file controller.h
\brief Controller related definitions. \brief Controller related definitions.
*/ */
#ifndef OPENRAVE_CONTROLLER_H #ifndef OPENRAVE_CONTROLLER_H
#define OPENRAVE_CONTROLLER_H #define OPENRAVE_CONTROLLER_H
namespace OpenRAVE { namespace OpenRAVE {
/** \brief <b>[interface]</b> Abstract base class to encapsulate a local co ntroller. See \ref arch_controller. /** \brief <b>[interface]</b> Abstract base class to encapsulate a local co ntroller. <b>Methods not multi-thread safe.</b> See \ref arch_controller.
\ingroup interfaces \ingroup interfaces
*/ */
class OPENRAVE_API ControllerBase : public InterfaceBase class OPENRAVE_API ControllerBase : public InterfaceBase
{ {
public: public:
ControllerBase(EnvironmentBasePtr penv) : InterfaceBase(PT_Controller, penv) {} ControllerBase(EnvironmentBasePtr penv) : InterfaceBase(PT_Controller, penv) {}
virtual ~ControllerBase() {} virtual ~ControllerBase() {}
/// \brief return the static interface type this class points to (used for safe casting) /// \brief return the static interface type this class points to (used for safe casting)
static inline InterfaceType GetInterfaceTypeStatic() { return PT_Contro ller; } static inline InterfaceType GetInterfaceTypeStatic() { return PT_Contro ller; }
skipping to change at line 95 skipping to change at line 95
/// \param fTimeElapsed - time elapsed in simulation environment since last frame /// \param fTimeElapsed - time elapsed in simulation environment since last frame
virtual void SimulationStep(dReal fTimeElapsed) = 0; virtual void SimulationStep(dReal fTimeElapsed) = 0;
/// \return true when goal reached. If a trajectory was set, return onl y when /// \return true when goal reached. If a trajectory was set, return onl y when
/// trajectory is done. If SetDesired was called, return only w hen robot is /// trajectory is done. If SetDesired was called, return only w hen robot is
/// is at the desired location. If SendCommand sent, returns tr ue when the command /// is at the desired location. If SendCommand sent, returns tr ue when the command
/// was completed by the hand. /// was completed by the hand.
virtual bool IsDone() = 0; virtual bool IsDone() = 0;
/// \return the time along the current command /// \return the time along the current command
virtual dReal GetTime() const { throw openrave_exception("ControllerBas e::GetTime not implemented",ORE_NotImplemented); } virtual dReal GetTime() const OPENRAVE_DUMMY_IMPLEMENTATION;
/// \brief get velocity of the controlled DOFs /// \brief get velocity of the controlled DOFs
/// \param vel [out] - current velocity of robot from the dof /// \param vel [out] - current velocity of robot from the dof
virtual void GetVelocity(std::vector<dReal>& vel) const { throw openrav e_exception("ControllerBase::GetVelocity not implemented",ORE_NotImplemente d); } virtual void GetVelocity(std::vector<dReal>& vel) const OPENRAVE_DUMMY_ IMPLEMENTATION;
/// get torque/current/strain values /// get torque/current/strain values
/// \param torque [out] - returns the current torque/current/strain exe rted by each of the dofs from outside forces. /// \param torque [out] - returns the current torque/current/strain exe rted by each of the dofs from outside forces.
/// The feedforward and friction terms should be subtracted out already /// The feedforward and friction terms should be subtracted out already
virtual void GetTorque(std::vector<dReal>& torque) const { throw openra virtual void GetTorque(std::vector<dReal>& torque) const OPENRAVE_DUMMY
ve_exception("ControllerBase::GetTorque not implemented",ORE_NotImplemented _IMPLEMENTATION;
); }
/// \deprecated (10/11/16)
virtual int GetActuatorState(int index) const RAVE_DEPRECATED { throw o
penrave_exception("actuator state deprecated"); }
// Specifies the controlled degrees of freedom used to control the r obot through torque In the // Specifies the controlled degrees of freedom used to control the r obot through torque In the
// general sense, it is not always the case that there's a one-to-on e mapping between a robot's // general sense, it is not always the case that there's a one-to-on e mapping between a robot's
// joints and the motors used to control the robot. A good example o f this is a // joints and the motors used to control the robot. A good example o f this is a
// differential-drive robot. If developers need such a robot, they s hould derive from RobotBase // differential-drive robot. If developers need such a robot, they s hould derive from RobotBase
// and override these methods. The function that maps control torque s to actual movements of // and override these methods. The function that maps control torque s to actual movements of
// the robot should be put in SimulationStep. As default, the contr ol degrees of freedom are // the robot should be put in SimulationStep. As default, the contr ol degrees of freedom are
// tied directly to the active degrees of freedom; the max torques f or affine dofs are 0 in // tied directly to the active degrees of freedom; the max torques f or affine dofs are 0 in
// this case. // this case.
// virtual void GetControlMaxTorques(std::vector<dReal>& vmaxtorque) con st; // virtual void GetControlMaxTorques(std::vector<dReal>& vmaxtorque) con st;
 End of changes. 4 change blocks. 
10 lines changed or deleted 5 lines changed or added


 environment.h   environment.h 
skipping to change at line 64 skipping to change at line 64
virtual InterfaceBasePtr CreateInterface(InterfaceType type,const std:: string& interfacename) RAVE_DEPRECATED =0; virtual InterfaceBasePtr CreateInterface(InterfaceType type,const std:: string& interfacename) RAVE_DEPRECATED =0;
/// \deprecated (10/09/23) see \ref RaveCreateRobot /// \deprecated (10/09/23) see \ref RaveCreateRobot
virtual RobotBasePtr CreateRobot(const std::string& name="") RAVE_DEPRE CATED =0; virtual RobotBasePtr CreateRobot(const std::string& name="") RAVE_DEPRE CATED =0;
/// \deprecated (10/09/23) see \ref RaveCreatePlanner /// \deprecated (10/09/23) see \ref RaveCreatePlanner
virtual PlannerBasePtr CreatePlanner(const std::string& name) RAVE_DEPR ECATED =0; virtual PlannerBasePtr CreatePlanner(const std::string& name) RAVE_DEPR ECATED =0;
/// \deprecated (10/09/23) see \ref RaveCreateSensorSystem /// \deprecated (10/09/23) see \ref RaveCreateSensorSystem
virtual SensorSystemBasePtr CreateSensorSystem(const std::string& name) RAVE_DEPRECATED =0; virtual SensorSystemBasePtr CreateSensorSystem(const std::string& name) RAVE_DEPRECATED =0;
/// \deprecated (10/09/23) see \ref RaveCreateController /// \deprecated (10/09/23) see \ref RaveCreateController
virtual ControllerBasePtr CreateController(const std::string& name) RAV E_DEPRECATED =0; virtual ControllerBasePtr CreateController(const std::string& name) RAV E_DEPRECATED =0;
/// \deprecated (10/09/23) see \ref RaveCreateProblem /// \deprecated (10/09/23) see \ref RaveCreateProblem
virtual ProblemInstancePtr CreateProblem(const std::string& name) RAVE_ DEPRECATED =0; virtual ModuleBasePtr CreateProblem(const std::string& name) RAVE_DEPRE CATED =0;
/// \deprecated (10/09/23) see \ref RaveCreateIkSolver /// \deprecated (10/09/23) see \ref RaveCreateIkSolver
virtual IkSolverBasePtr CreateIkSolver(const std::string& name) RAVE_DE PRECATED =0; virtual IkSolverBasePtr CreateIkSolver(const std::string& name) RAVE_DE PRECATED =0;
/// \deprecated (10/09/23) see \ref RaveCreatePhysicsEngine /// \deprecated (10/09/23) see \ref RaveCreatePhysicsEngine
virtual PhysicsEngineBasePtr CreatePhysicsEngine(const std::string& nam e) RAVE_DEPRECATED =0; virtual PhysicsEngineBasePtr CreatePhysicsEngine(const std::string& nam e) RAVE_DEPRECATED =0;
/// \deprecated (10/09/23) see \ref RaveCreateSensor /// \deprecated (10/09/23) see \ref RaveCreateSensor
virtual SensorBasePtr CreateSensor(const std::string& name) RAVE_DEPREC ATED =0; virtual SensorBasePtr CreateSensor(const std::string& name) RAVE_DEPREC ATED =0;
/// \deprecated (10/09/23) see \ref RaveCreateCollisionChecker /// \deprecated (10/09/23) see \ref RaveCreateCollisionChecker
virtual CollisionCheckerBasePtr CreateCollisionChecker(const std::strin g& name) RAVE_DEPRECATED =0; virtual CollisionCheckerBasePtr CreateCollisionChecker(const std::strin g& name) RAVE_DEPRECATED =0;
/// \deprecated (10/09/23) see \ref RaveCreateViewer /// \deprecated (10/09/23) see \ref RaveCreateViewer
virtual ViewerBasePtr CreateViewer(const std::string& name) RAVE_DEPREC ATED =0; virtual ViewerBasePtr CreateViewer(const std::string& name) RAVE_DEPREC ATED =0;
skipping to change at line 103 skipping to change at line 103
/// \brief Remove ownership of the interface. /// \brief Remove ownership of the interface.
virtual void DisownInterface(InterfaceBasePtr pinterface) = 0; virtual void DisownInterface(InterfaceBasePtr pinterface) = 0;
/// \brief Create and return a clone of the current environment. /// \brief Create and return a clone of the current environment.
/// ///
/// Clones do not share any memory or resource between each other. /// Clones do not share any memory or resource between each other.
/// or their parent making them ideal for performing separte planning e xperiments while keeping /// or their parent making them ideal for performing separte planning e xperiments while keeping
/// the parent environment unchanged. /// the parent environment unchanged.
/// By default a clone only copies the collision checkers and physics e ngine. /// By default a clone only copies the collision checkers and physics e ngine.
/// When bodies are cloned, the unique ids are preserved across environ ments (each body can be referenced with its id in both environments). The a ttached and grabbed bodies of each body/robot are also copied to the new en vironment. /// When bodies are cloned, the unique ids are preserved across environ ments (each body can be referenced with its id in both environments). The a ttached and grabbed bodies of each body/robot are also copied to the new en vironment.
/// \param options A set of CloningOptions describing what is actually cloned. /// \param options A set of \ref CloningOptions describing what is actu ally cloned.
/// \return An environment of the same type as this environment contain ing the copied information. /// \return An environment of the same type as this environment contain ing the copied information.
virtual EnvironmentBasePtr CloneSelf(int options) = 0; virtual EnvironmentBasePtr CloneSelf(int options) = 0;
/// \brief Each function takes an optional pointer to a CollisionReport structure and returns true if collision occurs. <b>[multi-thread safe]</b> /// \brief Each function takes an optional pointer to a CollisionReport structure and returns true if collision occurs. <b>[multi-thread safe]</b>
/// ///
/// \name Collision specific functions. /// \name Collision specific functions.
/// \anchor env_collision_checking /// \anchor env_collision_checking
//@{ //@{
/// set the global environment collision checker /// set the global environment collision checker
virtual bool SetCollisionChecker(CollisionCheckerBasePtr pchecker)=0; virtual bool SetCollisionChecker(CollisionCheckerBasePtr pchecker)=0;
skipping to change at line 199 skipping to change at line 199
/// ///
/// See \ref arch_simulation for more about the simulation thread. /// See \ref arch_simulation for more about the simulation thread.
virtual bool IsSimulationRunning() const = 0; virtual bool IsSimulationRunning() const = 0;
/// \brief Return simulation time since the start of the environment (i n microseconds). <b>[multi-thread safe]</b> /// \brief Return simulation time since the start of the environment (i n microseconds). <b>[multi-thread safe]</b>
/// ///
/// See \ref arch_simulation for more about the simulation thread. /// See \ref arch_simulation for more about the simulation thread.
virtual uint64_t GetSimulationTime() = 0; virtual uint64_t GetSimulationTime() = 0;
//@} //@}
/// \name XML Parsing, File Loading /// \name File Loading and Parsing
/// \anchor env_loading /// \anchor env_loading
//@{ //@{
/// \brief Loads a scene from an OpenRAVE XML file. <b>[multi-thread sa
fe]</b> /// \brief A set of options used to select particular parts of the scen
virtual bool Load(const std::string& filename) = 0; e
/// Loads a scene from XML-formatted data, environment is locked automa enum SelectionOptions
tically making this method thread-safe {
virtual bool LoadXMLData(const std::string& data) = 0; SO_NoRobots = 1, ///< everything but robots
/// Saves a scene depending on the filename extension. Default is in CO TO_Obstacles = 1, ///< everything but robots
LLADA format SO_Robots = 2, ///< all robots
virtual bool Save(const std::string& filename) = 0; TO_Robots = 2, ///< all robots
SO_Everything = 3, ///< all bodies and robots everything
TO_Everything = 3, ///< all bodies and robots everything
SO_Body = 4, ///< only triangulate robot/kinbody
TO_Body = 4, ///< only triangulate robot/kinbody
SO_AllExceptBody = 5, ///< select everything but the robot/kinbody
TO_AllExceptBody = 5, ///< select everything but the robot/kinbody
SO_BodyList = 6, ///< provide a list of body names
};
typedef SelectionOptions TriangulateOptions;
/// \brief Loads a scene from a file and adds all objects in the enviro
nment. <b>[multi-thread safe]</b>
virtual bool Load(const std::string& filename, const AttributesList& at
ts = AttributesList()) = 0;
/// \brief Loads a scene from in-memory data and adds all objects in th
e environment. <b>[multi-thread safe]</b>
virtual bool LoadData(const std::string& data, const AttributesList& at
ts = AttributesList()) = 0;
virtual bool LoadXMLData(const std::string& data, const AttributesList&
atts = AttributesList()) { return LoadData(data,atts); }
/// \brief Saves a scene depending on the filename extension. Default i
s in COLLADA format
///
/// \param filename the filename to save the results at
/// \param options controls what to save
/// \param selectname
/// \throw openrave_exception Throw if failed to save anything
virtual void Save(const std::string& filename, SelectionOptions options
=SO_Everything, const std::string& selectname="") = 0;
/** \brief Initializes a robot from a resource file. The robot is not a dded to the environment when calling this function. <b>[multi-thread safe]< /b> /** \brief Initializes a robot from a resource file. The robot is not a dded to the environment when calling this function. <b>[multi-thread safe]< /b>
\param robot If a null pointer is passed, a new robot will be creat ed, otherwise an existing robot will be filled \param robot If a null pointer is passed, a new robot will be creat ed, otherwise an existing robot will be filled
\param filename the name of the resource file, its extension determ ines the format of the file. See \ref supported_formats. \param filename the name of the resource file, its extension determ ines the format of the file. See \ref supported_formats.
\param atts The attribute/value pair specifying loading options. De fined in \ref arch_robot. \param atts The attribute/value pair specifying loading options. De fined in \ref arch_robot.
*/ */
virtual RobotBasePtr ReadRobotXMLFile(RobotBasePtr robot, const std::st virtual RobotBasePtr ReadRobotURI(RobotBasePtr robot, const std::string
ring& filename, const AttributesList& atts = AttributesList()) = 0; & filename, const AttributesList& atts = AttributesList()) = 0;
/// \brief Creates a new robot from an XML file with no extra load opti virtual RobotBasePtr ReadRobotXMLFile(RobotBasePtr robot, const std::st
ons specified. <b>[multi-thread safe]</b> ring& filename, const AttributesList& atts = AttributesList()) { return Rea
virtual RobotBasePtr ReadRobotXMLFile(const std::string& filename) = 0; dRobotURI(robot,filename,atts); }
/** \brief Initialize a robot from an XML formatted string. <b>[multi-t /// \brief Creates a new robot from a file with no extra load options s
hread safe]</b> pecified. <b>[multi-thread safe]</b>
virtual RobotBasePtr ReadRobotURI(const std::string& filename) { return
ReadRobotURI(RobotBasePtr(),filename,AttributesList()); }
virtual RobotBasePtr ReadRobotXMLFile(const std::string& filename) { re
turn ReadRobotURI(filename); }
/** \brief Initialize a robot from in-memory data. <b>[multi-thread saf
e]</b>
The robot should not be added the environment when calling this fun ction. The robot should not be added the environment when calling this fun ction.
\param robot If a null pointer is passed, a new robot will be creat ed, otherwise an existing robot will be filled \param robot If a null pointer is passed, a new robot will be creat ed, otherwise an existing robot will be filled
\param atts The attribute/value pair specifying loading options. De fined in \ref arch_robot. \param atts The attribute/value pair specifying loading options. De fined in \ref arch_robot.
*/ */
virtual RobotBasePtr ReadRobotXMLData(RobotBasePtr robot, const std::st virtual RobotBasePtr ReadRobotData(RobotBasePtr robot, const std::strin
ring& data, const AttributesList& atts = AttributesList()) = 0; g& data, const AttributesList& atts = AttributesList()) = 0;
virtual RobotBasePtr ReadRobotXMLData(RobotBasePtr robot, const std::st
ring& data, const AttributesList& atts = AttributesList()) { return ReadRob
otData(robot,data,atts); }
/** \brief Initializes a kinematic body from a resource file. The body is not added to the environment when calling this function. <b>[multi-threa d safe]</b> /** \brief Initializes a kinematic body from a resource file. The body is not added to the environment when calling this function. <b>[multi-threa d safe]</b>
\param filename the name of the resource file, its extension determ ines the format of the file. See \ref supported_formats. \param filename the name of the resource file, its extension determ ines the format of the file. See \ref supported_formats.
\param body If a null pointer is passed, a new body will be created , otherwise an existing robot will be filled \param body If a null pointer is passed, a new body will be created , otherwise an existing robot will be filled
\param atts The attribute/value pair specifying loading options. De fined in \ref arch_kinbody. \param atts The attribute/value pair specifying loading options. De fined in \ref arch_kinbody.
*/ */
virtual KinBodyPtr ReadKinBodyXMLFile(KinBodyPtr body, const std::strin virtual KinBodyPtr ReadKinBodyURI(KinBodyPtr body, const std::string& f
g& filename, const AttributesList& atts = AttributesList()) = 0; ilename, const AttributesList& atts = AttributesList()) = 0;
virtual KinBodyPtr ReadKinBodyXMLFile(KinBodyPtr body, const std::strin
g& filename, const AttributesList& atts = AttributesList()) { return ReadKi
nBodyURI(body,filename,atts); }
/// \brief Creates a new kinbody from an XML file with no extra load op tions specified. <b>[multi-thread safe]</b> /// \brief Creates a new kinbody from an XML file with no extra load op tions specified. <b>[multi-thread safe]</b>
virtual KinBodyPtr ReadKinBodyXMLFile(const std::string& filename) = 0; virtual KinBodyPtr ReadKinBodyURI(const std::string& filename) { return
ReadKinBodyURI(KinBodyPtr(),filename,AttributesList()); }
virtual KinBodyPtr ReadKinBodyXMLFile(const std::string& filename) { re
turn ReadKinBodyURI(filename); }
/** \brief Initializes a kinematic body from an XML formatted string. < b>[multi-thread safe]</b> /** \brief Initializes a kinematic body from in-memory data. <b>[multi- thread safe]</b>
The body should not be added to the environment when calling this f unction. The body should not be added to the environment when calling this f unction.
\param body If a null pointer is passed, a new body will be created , otherwise an existing robot will be filled \param body If a null pointer is passed, a new body will be created , otherwise an existing robot will be filled
\param atts The attribute/value pair specifying loading options. De fined in \ref arch_kinbody. \param atts The attribute/value pair specifying loading options. De fined in \ref arch_kinbody.
*/ */
virtual KinBodyPtr ReadKinBodyXMLData(KinBodyPtr body, const std::strin virtual KinBodyPtr ReadKinBodyData(KinBodyPtr body, const std::string&
g& data, const AttributesList& atts = AttributesList()) = 0; data, const AttributesList& atts = AttributesList()) = 0;
virtual KinBodyPtr ReadKinBodyXMLData(KinBodyPtr body, const std::strin
g& data, const AttributesList& atts = AttributesList()) { return ReadKinBod
yData(body,data,atts); }
/** \brief Initializes an interface from a resource file. <b>[multi-thr ead safe]</b> /** \brief Initializes an interface from a resource file. <b>[multi-thr ead safe]</b>
\param pinterface If a null pointer is passed, a new interface will be created, otherwise an existing interface will be filled \param pinterface If a null pointer is passed, a new interface will be created, otherwise an existing interface will be filled
\param filename the name of the resource file, its extension determ ines the format of the file. See \ref supported_formats. \param filename the name of the resource file, its extension determ ines the format of the file. See \ref supported_formats.
\param atts The attribute/value pair specifying loading options. Se e the individual interface descriptions at \ref interface_concepts. \param atts The attribute/value pair specifying loading options. Se e the individual interface descriptions at \ref interface_concepts.
*/ */
virtual InterfaceBasePtr ReadInterfaceXMLFile(InterfaceBasePtr pinterfa virtual InterfaceBasePtr ReadInterfaceURI(InterfaceBasePtr pinterface,
ce, InterfaceType type, const std::string& filename, const AttributesList& InterfaceType type, const std::string& filename, const AttributesList& atts
atts = AttributesList()) = 0; = AttributesList()) = 0;
virtual InterfaceBasePtr ReadInterfaceXMLFile(const std::string& filena virtual InterfaceBasePtr ReadInterfaceXMLFile(InterfaceBasePtr pinterfa
me, const AttributesList& atts = AttributesList()) = 0; ce, InterfaceType type, const std::string& filename, const AttributesList&
atts = AttributesList()) { return ReadInterfaceURI(pinterface,type,filename
,atts); }
/** \brief Initializes an interface from an XML formatted string. <b>[m virtual InterfaceBasePtr ReadInterfaceURI(const std::string& filename,
ulti-thread safe]</b> const AttributesList& atts = AttributesList()) = 0;
virtual InterfaceBasePtr ReadInterfaceXMLFile(const std::string& filena
me, const AttributesList& atts = AttributesList()) { return ReadInterfaceUR
I(filename,atts); }
/** \brief Initializes an interface from in-memory data. <b>[multi-thre
ad safe]</b>
\param pinterface If a null pointer is passed, a new interface will be created, otherwise an existing interface will be filled \param pinterface If a null pointer is passed, a new interface will be created, otherwise an existing interface will be filled
\param data string containing XML data \param data string containing data
\param atts The attribute/value pair specifying loading options. Se e the individual interface descriptions at \ref interface_concepts. \param atts The attribute/value pair specifying loading options. Se e the individual interface descriptions at \ref interface_concepts.
*/ */
virtual InterfaceBasePtr ReadInterfaceXMLData(InterfaceBasePtr pinterfa virtual InterfaceBasePtr ReadInterfaceData(InterfaceBasePtr pinterface,
ce, InterfaceType type, const std::string& data, const AttributesList& atts InterfaceType type, const std::string& data, const AttributesList& atts =
= AttributesList()) = 0; AttributesList()) = 0;
virtual InterfaceBasePtr ReadInterfaceXMLData(InterfaceBasePtr pinterfa
ce, InterfaceType type, const std::string& data, const AttributesList& atts
= AttributesList()) { return ReadInterfaceData(pinterface,type,data,atts);
}
/** \brief reads in the rigid geometry of a resource file into a TRIMES H structure /** \brief reads in the rigid geometry of a resource file into a TRIMES H structure
\param filename the name of the resource file, its extension determ ines the format of the file. Complex meshes and articulated meshes are all triangulated appropriately. See \ref supported_formats. \param filename the name of the resource file, its extension determ ines the format of the file. Complex meshes and articulated meshes are all triangulated appropriately. See \ref supported_formats.
\param options Options to control the parsing process. \param options Options to control the parsing process.
*/ */
virtual boost::shared_ptr<KinBody::Link::TRIMESH> ReadTrimeshFile(boost virtual boost::shared_ptr<KinBody::Link::TRIMESH> ReadTrimeshURI(boost:
::shared_ptr<KinBody::Link::TRIMESH> ptrimesh, const std::string& filename, :shared_ptr<KinBody::Link::TRIMESH> ptrimesh, const std::string& filename,
const AttributesList& atts = AttributesList()) = 0; const AttributesList& atts = AttributesList()) = 0;
virtual boost::shared_ptr<KinBody::Link::TRIMESH> ReadTrimeshFile(boost
::shared_ptr<KinBody::Link::TRIMESH> ptrimesh, const std::string& filename,
const AttributesList& atts = AttributesList()) { return ReadTrimeshURI(ptr
imesh,filename,atts); }
/// \deprecated (10/09/30) see \ref RaveRegisterXMLReader /// \deprecated (10/09/30) see \ref RaveRegisterXMLReader
virtual boost::shared_ptr<void> RegisterXMLReader(InterfaceType type, c onst std::string& xmltag, const CreateXMLReaderFn& fn) RAVE_DEPRECATED = 0; virtual boost::shared_ptr<void> RegisterXMLReader(InterfaceType type, c onst std::string& xmltag, const CreateXMLReaderFn& fn) RAVE_DEPRECATED = 0;
/// \brief Parses a file for OpenRAVE XML formatted data. /// \brief Parses a file for OpenRAVE XML formatted data.
virtual bool ParseXMLFile(BaseXMLReaderPtr preader, const std::string& filename) = 0; virtual bool ParseXMLFile(BaseXMLReaderPtr preader, const std::string& filename) RAVE_DEPRECATED = 0;
/** \brief Parses a data file for XML data. /** \brief Parses a data file for XML data.
\param pdata The data of the buffer \param pdata The data of the buffer
\param len the number of bytes valid in pdata \param len the number of bytes valid in pdata
*/ */
virtual bool ParseXMLData(BaseXMLReaderPtr preader, const std::string& data) = 0; virtual bool ParseXMLData(BaseXMLReaderPtr preader, const std::string& data) RAVE_DEPRECATED = 0;
//@} //@}
/// \name Object Setting and Querying /// \name Object Setting and Querying
/// \anchor env_objects /// \anchor env_objects
//@{ //@{
/// \brief Add a body to the environment /// \brief Add a body to the environment
/// ///
/// \param[in] body the pointer to an initialized body /// \param[in] body the pointer to an initialized body
/// \param[in] bAnonymous if true and there exists a body/robot with th e same name, will make body's name unique /// \param[in] bAnonymous if true and there exists a body/robot with th e same name, will make body's name unique
virtual bool AddKinBody(KinBodyPtr body, bool bAnonymous=false) = 0; /// \throw openrave_exception Throw if body is invalid or already added
virtual void AddKinBody(KinBodyPtr body, bool bAnonymous=false) = 0;
/// \brief add a robot to the environment /// \brief add a robot to the environment
/// ///
/// \param[in] robot the pointer to an initialized robot /// \param[in] robot the pointer to an initialized robot
/// \param[in] bAnonymous if true and there exists a body/robot with th e same name, will make robot's name unique /// \param[in] bAnonymous if true and there exists a body/robot with th e same name, will make robot's name unique
virtual bool AddRobot(RobotBasePtr robot, bool bAnonymous=false) = 0; /// \throw openrave_exception Throw if robot is invalid or already adde
d
virtual void AddRobot(RobotBasePtr robot, bool bAnonymous=false) = 0;
/// \brief registers the sensor with the environment and turns its powe r on. /// \brief registers the sensor with the environment and turns its powe r on.
/// ///
/// \param[in] sensor the pointer to an initialized sensor /// \param[in] sensor the pointer to an initialized sensor
/// \param[in] bAnonymous if true and there exists a sensor with the sa me name, will make sensor's name unique /// \param[in] bAnonymous if true and there exists a sensor with the sa me name, will make sensor's name unique
virtual bool AddSensor(SensorBasePtr sensor, bool bAnonymous=false) = 0 /// \throw openrave_exception Throw if sensor is invalid or already add
; ed
virtual void AddSensor(SensorBasePtr sensor, bool bAnonymous=false) = 0
;
/// \brief Fill an array with all sensors loaded in the environment. <b
>[multi-thread safe]</b>
///
/// The sensors come from the currently loaded robots and the explicitl
y added sensors
virtual void GetSensors(std::vector<SensorBasePtr>& sensors) const = 0;
/// \deprecated (10/09/15) see \ref EnvironmentBase::Remove /// \deprecated (10/09/15) see \ref EnvironmentBase::Remove
virtual bool RemoveKinBody(KinBodyPtr body) RAVE_DEPRECATED = 0; virtual bool RemoveKinBody(KinBodyPtr body) RAVE_DEPRECATED = 0;
/// \brief Removes a currently loaded interface from the environment. < b>[multi-thread safe]</b> /// \brief Removes a currently loaded interface from the environment. < b>[multi-thread safe]</b>
/// ///
/// The function removes currently loaded bodies, robots, sensors, prob lems from the actively used /// The function removes currently loaded bodies, robots, sensors, prob lems from the actively used
/// interfaces of the environment. This does not destroy the interface, but it does remove all /// interfaces of the environment. This does not destroy the interface, but it does remove all
/// references managed. Some interfaces like problems have destroy meth ods that are called to signal /// references managed. Some interfaces like problems have destroy meth ods that are called to signal
/// unloading. Note that the active interfaces are different from the o wned interfaces. /// unloading. Note that the active interfaces are different from the o wned interfaces.
skipping to change at line 337 skipping to change at line 385
/// \return first Robot that matches the name /// \return first Robot that matches the name
virtual RobotBasePtr GetRobot(const std::string& name)=0; virtual RobotBasePtr GetRobot(const std::string& name)=0;
/// \brief Get all bodies loaded in the environment (including robots). <b>[multi-thread safe]</b> /// \brief Get all bodies loaded in the environment (including robots). <b>[multi-thread safe]</b>
/// \param[out] bodies filled with all the bodies /// \param[out] bodies filled with all the bodies
virtual void GetBodies(std::vector<KinBodyPtr>& bodies) const = 0; virtual void GetBodies(std::vector<KinBodyPtr>& bodies) const = 0;
/// \brief Fill an array with all robots loaded in the environment. <b> [multi-thread safe]</b> /// \brief Fill an array with all robots loaded in the environment. <b> [multi-thread safe]</b>
virtual void GetRobots(std::vector<RobotBasePtr>& robots) const = 0; virtual void GetRobots(std::vector<RobotBasePtr>& robots) const = 0;
/// \brief Fill an array with all sensors loaded in the environment. <b >[multi-thread safe]</b> /// \brief adds a viewer to the environment
/// ///
/// The sensors come from the currently loaded robots and the explicitl /// \throw openrave_exception Throw if body is invalid or already added
y added sensors virtual void AddViewer(ViewerBasePtr pviewer) = 0;
virtual void GetSensors(std::vector<SensorBasePtr>& sensors) const = 0;
/// \deprecated (11/06/13) see AddViewer
virtual bool AttachViewer(ViewerBasePtr pnewviewer) RAVE_DEPRECATED { A
ddViewer(pnewviewer); return true; }
/// \brief Return a viewer with a particular name.
///
/// When no name is specified, the first loaded viewer is returned.
virtual ViewerBasePtr GetViewer(const std::string& name="") const = 0;
/// \brief Returns a list of loaded viewers with a pointer to a lock pr
eventing the list from being modified.
///
/// As long as the lock is held, the problems are guaranteed to stay lo
aded in the environment.
/// \return returns a pointer to a Lock. Destroying the shared_ptr will
release the lock
virtual boost::shared_ptr<boost::mutex::scoped_lock> GetViewers(std::li
st<ViewerBasePtr>& listViewers) const = 0;
/// \brief Retrieve published bodies, completes even if environment is locked. <b>[multi-thread safe]</b> /// \brief Retrieve published bodies, completes even if environment is locked. <b>[multi-thread safe]</b>
/// ///
/// Note that the pbody pointer might become invalid as soon as GetPubl ishedBodies returns. /// Note that the pbody pointer might become invalid as soon as GetPubl ishedBodies returns.
virtual void GetPublishedBodies(std::vector<KinBody::BodyState>& vbodie s) = 0; virtual void GetPublishedBodies(std::vector<KinBody::BodyState>& vbodie s) = 0;
/// updates the published bodies that viewers and other programs listen ing in on the environment see. /// updates the published bodies that viewers and other programs listen ing in on the environment see.
/// For example, calling this function inside a planning loop allows th e viewer to update the environment /// For example, calling this function inside a planning loop allows th e viewer to update the environment
/// reflecting the status of the planner. /// reflecting the status of the planner.
/// Assumes that the physics are locked. /// Assumes that the physics are locked.
virtual void UpdatePublishedBodies() = 0; virtual void UpdatePublishedBodies() = 0;
/// Get the corresponding body from its unique network id /// Get the corresponding body from its unique network id
virtual KinBodyPtr GetBodyFromEnvironmentId(int id) = 0; virtual KinBodyPtr GetBodyFromEnvironmentId(int id) = 0;
virtual KinBodyPtr GetBodyFromNetworkId(int id) RAVE_DEPRECATED = 0;
/// A set of options specifying what to triangulate
enum TriangulateOptions
{
TO_Obstacles = 1, ///< everything but robots
TO_Robots = 2, ///< all robots
TO_Everything = 3, ///< all bodies and robots everything
TO_Body = 4, ///< only triangulate kinbody
TO_AllExceptBody = 5 ///< triangulate everything but kinbody
};
/// \brief Triangulation of the body including its current transformati on. trimesh will be appended the new data. <b>[multi-thread safe]</b> /// \brief Triangulation of the body including its current transformati on. trimesh will be appended the new data. <b>[multi-thread safe]</b>
/// ///
/// \param[out] trimesh - The output triangle mesh /// \param[out] trimesh - The output triangle mesh
/// \param[in] body body the triangulate /// \param[in] body body the triangulate
virtual bool Triangulate(KinBody::Link::TRIMESH& trimesh, KinBodyConstP /// \throw openrave_exception Throw if failed to add anything
tr pbody) = 0; virtual void Triangulate(KinBody::Link::TRIMESH& trimesh, KinBodyConstP
tr pbody) = 0;
/// \brief General triangulation of the whole scene. trimesh will be ap pended the new data. <b>[multi-thread safe]</b> /// \brief General triangulation of the whole scene. <b>[multi-thread s afe]</b>
/// ///
/// \param[out] trimesh - The output triangle mesh /// \param[out] trimesh - The output triangle mesh. The new triangles a
/// \param[in] options - Controlls what to triangulate re appended to the existing triangles!
/// \param[in] name - name of the body used in options /// \param[in] options - Controlls what to triangulate.
virtual bool TriangulateScene(KinBody::Link::TRIMESH& trimesh, Triangul /// \param[in] selectname - name of the body used in options
ateOptions options, const std::string& name) = 0; /// \throw openrave_exception Throw if failed to add anything
virtual void TriangulateScene(KinBody::Link::TRIMESH& trimesh, Selectio
nOptions options, const std::string& selectname) = 0;
//@} //@}
/// \brief Load a new problem, need to Lock if calling outside simulati /// \brief Load a new module, need to Lock if calling outside simulatio
on thread n thread
virtual int LoadProblem(ProblemInstancePtr prob, const std::string& cmd virtual int AddModule(ModuleBasePtr module, const std::string& cmdargs)
args) = 0; = 0;
virtual int LoadProblem(ModuleBasePtr module, const std::string& cmdarg
s) { return AddModule(module,cmdargs); }
/// \deprecated (10/09/15) see \ref EnvironmentBase::Remove /// \deprecated (10/09/15) see \ref EnvironmentBase::Remove
virtual bool RemoveProblem(ProblemInstancePtr prob) RAVE_DEPRECATED = 0 ; virtual bool RemoveProblem(ModuleBasePtr prob) RAVE_DEPRECATED = 0;
/// \brief Returns a list of loaded problems with a pointer to a lock p reventing the list from being modified. /// \brief Returns a list of loaded problems with a pointer to a lock p reventing the list from being modified.
/// ///
/// As long as the lock is held, the problems are guaranteed to stay lo aded in the environment. /// As long as the lock is held, the problems are guaranteed to stay lo aded in the environment.
/// \return returns a pointer to a Lock. Destroying the shared_ptr will release the lock /// \return returns a pointer to a Lock. Destroying the shared_ptr will release the lock
virtual boost::shared_ptr<void> GetLoadedProblems(std::list<ProblemInst virtual boost::shared_ptr<void> GetModules(std::list<ModuleBasePtr>& li
ancePtr>& listProblems) const = 0; stModules) const = 0;
virtual boost::shared_ptr<void> GetLoadedProblems(std::list<ModuleBaseP
tr>& listModules) const { return GetModules(listModules); }
/// \brief Return the global environment mutex used to protect environm ent information access in multi-threaded environments. /// \brief Return the global environment mutex used to protect environm ent information access in multi-threaded environments.
/// ///
/// Accessing environment body information and adding/removing bodies /// Accessing environment body information and adding/removing bodies
/// or changing any type of scene property should have the environment lock acquired. Once the environment /// or changing any type of scene property should have the environment lock acquired. Once the environment
/// is locked, the user is guaranteed that nnothing will change in the environment. /// is locked, the user is guaranteed that nnothing will change in the environment.
virtual EnvironmentMutex& GetMutex() const = 0; virtual EnvironmentMutex& GetMutex() const = 0;
virtual bool AttachViewer(ViewerBasePtr pnewviewer) = 0;
virtual ViewerBasePtr GetViewer() const = 0;
/// \name 3D plotting methods. /// \name 3D plotting methods.
/// \anchor env_plotting /// \anchor env_plotting
//@{ //@{
/// \deprecated (10/11/05) /// \deprecated (10/11/05)
typedef OpenRAVE::GraphHandlePtr GraphHandlePtr RAVE_DEPRECATED; typedef OpenRAVE::GraphHandlePtr GraphHandlePtr RAVE_DEPRECATED;
/// \brief Plot a point cloud with one color. <b>[multi-thread safe]</b > /// \brief Plot a point cloud with one color. <b>[multi-thread safe]</b >
/// ///
/// \param ppoints array of points /// \param ppoints array of points
skipping to change at line 501 skipping to change at line 555
/// \deprecated (10/09/23) see \ref RaveGetHomeDirectory /// \deprecated (10/09/23) see \ref RaveGetHomeDirectory
virtual const std::string& GetHomeDirectory() const RAVE_DEPRECATED = 0 ; virtual const std::string& GetHomeDirectory() const RAVE_DEPRECATED = 0 ;
//@{ debug/global commands //@{ debug/global commands
/// sets the debug level /// sets the debug level
/// \param level 0 for no debug, 1 - to print all debug messeges. Defau lt /// \param level 0 for no debug, 1 - to print all debug messeges. Defau lt
/// value for release builds is 0, for debug builds it is 1 /// value for release builds is 0, for debug builds it is 1
/// declaring variables with stdcall can be a little complex /// declaring variables with stdcall can be a little complex
virtual void SetDebugLevel(DebugLevel level) = 0; virtual void SetDebugLevel(uint32_t level) = 0;
virtual DebugLevel GetDebugLevel() const = 0; virtual uint32_t GetDebugLevel() const = 0;
//@} //@}
protected: protected:
virtual const char* GetHash() const { return OPENRAVE_ENVIRONMENT_HASH; } virtual const char* GetHash() const { return OPENRAVE_ENVIRONMENT_HASH; }
private: private:
UserDataPtr __pUserData; ///< \see GetUserData UserDataPtr __pUserData; ///< \see GetUserData
int __nUniqueId; ///< \see GetId int __nUniqueId; ///< \see GetId
}; };
} // end namespace OpenRAVE } // end namespace OpenRAVE
 End of changes. 32 change blocks. 
82 lines changed or deleted 175 lines changed or added


 geometry.h   geometry.h 
skipping to change at line 236 skipping to change at line 236
T fnorm = rot.lengthsqr4(); T fnorm = rot.lengthsqr4();
MATH_ASSERT( fnorm > 0.99f && fnorm < 1.01f ); MATH_ASSERT( fnorm > 0.99f && fnorm < 1.01f );
} }
inline RaveTransform(const RaveTransformMatrix<T>& t); inline RaveTransform(const RaveTransformMatrix<T>& t);
void identity() { void identity() {
rot.x = 1; rot.y = rot.z = rot.w = 0; rot.x = 1; rot.y = rot.z = rot.w = 0;
trans.x = trans.y = trans.z = 0; trans.x = trans.y = trans.z = 0;
} }
/// \deprecated (10/07/26) use quatFromAxisAngle
template <typename U> inline RaveTransform<T>& rotfromaxisangle(const R
aveVector<U>& axis, U angle) RAVE_DEPRECATED;
/// transform a 3 dim vector /// transform a 3 dim vector
inline RaveVector<T> operator* (const RaveVector<T>& r) const { inline RaveVector<T> operator* (const RaveVector<T>& r) const {
return trans + rotate(r); return trans + rotate(r);
} }
/// transform a vector by the rotation component only /// transform a vector by the rotation component only
inline RaveVector<T> rotate(const RaveVector<T>& r) const { inline RaveVector<T> rotate(const RaveVector<T>& r) const {
T xx = 2 * rot.y * rot.y; T xx = 2 * rot.y * rot.y;
T xy = 2 * rot.y * rot.z; T xy = 2 * rot.y * rot.z;
T xz = 2 * rot.y * rot.w; T xz = 2 * rot.y * rot.w;
skipping to change at line 348 skipping to change at line 345
} }
inline RaveTransformMatrix(const RaveTransform<T>& t); inline RaveTransformMatrix(const RaveTransform<T>& t);
inline void identity() { inline void identity() {
m[0] = 1; m[1] = 0; m[2] = 0; m[0] = 1; m[1] = 0; m[2] = 0;
m[4] = 0; m[5] = 1; m[6] = 0; m[4] = 0; m[5] = 1; m[6] = 0;
m[8] = 0; m[9] = 0; m[10] = 1; m[8] = 0; m[9] = 0; m[10] = 1;
trans.x = trans.y = trans.z = 0; trans.x = trans.y = trans.z = 0;
} }
/// \deprecated (10/07/26) use matrixFromAxisAngle
template <typename U> inline RaveTransformMatrix<T>& rotfromaxisangle(c
onst RaveVector<U>& axis, U angle) RAVE_DEPRECATED;
inline void rotfrommat(T m_00, T m_01, T m_02, T m_10, T m_11, T m_12, T m_20, T m_21, T m_22) { inline void rotfrommat(T m_00, T m_01, T m_02, T m_10, T m_11, T m_12, T m_20, T m_21, T m_22) {
m[0] = m_00; m[1] = m_01; m[2] = m_02; m[3] = 0; m[0] = m_00; m[1] = m_01; m[2] = m_02; m[3] = 0;
m[4] = m_10; m[5] = m_11; m[6] = m_12; m[7] = 0; m[4] = m_10; m[5] = m_11; m[6] = m_12; m[7] = 0;
m[8] = m_20; m[9] = m_21; m[10] = m_22; m[11] = 0; m[8] = m_20; m[9] = m_21; m[10] = m_22; m[11] = 0;
} }
inline T rot(int i, int j) const { inline T rot(int i, int j) const {
MATH_ASSERT( i >= 0 && i < 3 && j >= 0 && j < 3); MATH_ASSERT( i >= 0 && i < 3 && j >= 0 && j < 3);
return m[4*i+j]; return m[4*i+j];
} }
skipping to change at line 529 skipping to change at line 523
template <typename T> template <typename T>
class frustum class frustum
{ {
public: public:
RaveVector<T> right, up, dir, pos; RaveVector<T> right, up, dir, pos;
T fnear, ffar; T fnear, ffar;
T ffovx,ffovy; T ffovx,ffovy;
T fcosfovx,fsinfovx,fcosfovy,fsinfovy; T fcosfovx,fsinfovx,fcosfovy,fsinfovy;
}; };
/// \brief intrinsic parameters for a camera.
template <typename T>
class RaveCameraIntrinsics
{
public:
RaveCameraIntrinsics() : fx(0),fy(0),cx(0),cy(0), focal_length(0.01) {}
RaveCameraIntrinsics(T fx, T fy, T cx, T cy) : fx(fx), fy(fy), cx(cx),
cy(cy), focal_length(0.01) {}
template <typename U>
RaveCameraIntrinsics<T>& operator=(const RaveCameraIntrinsics<U>& r)
{
distortion_model = r.distortion_model;
distortion_coeffs.resize(r.distortion_coeffs.size());
std::copy(r.distortion_coeffs.begin(),r.distortion_coeffs.end(),dis
tortion_coeffs.begin());
focal_length = r.focal_length;
fx = r.fx;
fy = r.fy;
cx = r.cx;
cy = r.cy;
}
T fx,fy, cx,cy;
/** \brief distortion model of the camera. if left empty, no distortion
model is used.
Possible values are:
- "plumb_bob" - Brown. "Decentering Distortion of Lenses", Photomet
ric Engineering, pages 444-462, Vol. 32, No. 3, 1966
*/
std::string distortion_model;
std::vector<T> distortion_coeffs; ///< coefficients of the distortion m
odel
T focal_length; ///< physical focal length distance since focal length
cannot be recovered from the intrinsic matrix, but is necessary for determi
ning the lens plane.
};
/// Don't add new lines to the output << operators. Some applications use i t to serialize the data /// Don't add new lines to the output << operators. Some applications use i t to serialize the data
/// to send across the network. /// to send across the network.
/// \name Primitive Serialization functions. /// \name Primitive Serialization functions.
//@{ //@{
template <typename U> template <typename U>
std::ostream& operator<<(std::ostream& O, const RaveVector<U>& v) std::ostream& operator<<(std::ostream& O, const RaveVector<U>& v)
{ {
return O << v.x << " " << v.y << " " << v.z << " " << v.w << " "; return O << v.x << " " << v.y << " " << v.z << " " << v.w << " ";
} }
skipping to change at line 804 skipping to change at line 831
T ratioA = MATH_SIN((1 - t) * halfTheta) / sinHalfTheta; T ratioA = MATH_SIN((1 - t) * halfTheta) / sinHalfTheta;
T ratioB = MATH_SIN(t * halfTheta) / sinHalfTheta; T ratioB = MATH_SIN(t * halfTheta) / sinHalfTheta;
//calculate Quaternion. //calculate Quaternion.
qm.w = (quat0.w * ratioA + qb.w * ratioB); qm.w = (quat0.w * ratioA + qb.w * ratioB);
qm.x = (quat0.x * ratioA + qb.x * ratioB); qm.x = (quat0.x * ratioA + qb.x * ratioB);
qm.y = (quat0.y * ratioA + qb.y * ratioB); qm.y = (quat0.y * ratioA + qb.y * ratioB);
qm.z = (quat0.z * ratioA + qb.z * ratioB); qm.z = (quat0.z * ratioA + qb.z * ratioB);
return qm; return qm;
} }
/// \deprecated (10/07/26) use quatSlerp
template <typename T>
inline RaveVector<T> dQSlerp(const RaveVector<T>& qa, const RaveVector<T>&
_qb, T t) RAVE_DEPRECATED;
template <typename T> template <typename T>
inline RaveVector<T> dQSlerp(const RaveVector<T>& qa, const RaveVector<T>& _qb, T t) inline RaveVector<T> dQSlerp(const RaveVector<T>& qa, const RaveVector<T>& _qb, T t)
{ {
return quatSlerp<T>(qa,_qb,t); return quatSlerp<T>(qa,_qb,t);
} }
/// \deprecated (10/07/26) use quatFromAxisAngle
template <typename T> inline RaveVector<T> AxisAngle2Quat(const RaveVector<
T>& rotaxis, T angle) RAVE_DEPRECATED;
template <typename T> inline RaveVector<T> AxisAngle2Quat(const RaveVector<
T>& rotaxis, T angle)
{
angle *= (T)0.5;
T fsin = MATH_SIN(angle);
return RaveVector<T>(MATH_COS(angle), rotaxis.x*fsin, rotaxis.y * fsin,
rotaxis.z * fsin);
}
/// \brief transform a vector by a quaternion /// \brief transform a vector by a quaternion
/// ///
/// \ingroup affine_math /// \ingroup affine_math
/// \param /// \param
template <typename T> template <typename T>
RaveVector<T> quatRotate(const RaveVector<T>& q, const RaveVector<T>& t) RaveVector<T> quatRotate(const RaveVector<T>& q, const RaveVector<T>& t)
{ {
T xx = 2 * q.y * q.y; T xx = 2 * q.y * q.y;
T xy = 2 * q.y * q.z; T xy = 2 * q.y * q.z;
T xz = 2 * q.y * q.w; T xz = 2 * q.y * q.w;
skipping to change at line 940 skipping to change at line 953
} }
template <typename T> template <typename T>
RaveTransformMatrix<T>::RaveTransformMatrix(const RaveTransform<T>& t) RaveTransformMatrix<T>::RaveTransformMatrix(const RaveTransform<T>& t)
{ {
matrixFromQuat(*this, t.rot); matrixFromQuat(*this, t.rot);
trans = t.trans; trans = t.trans;
} }
template <typename T> template <typename U> inline RaveTransformMatrix<T>&
RaveTransformMatrix<T>::rotfromaxisangle(const RaveVector<U>& axis, U angle
)
{
*this = matrixFromAxisAngle(axis,angle);
}
template <typename T> template <typename U> inline RaveTransform<T>& RaveTr
ansform<T>::rotfromaxisangle(const RaveVector<U>& axis, U angle) {
U sinang = (U)MATH_SIN(angle/2);
rot.x = (U)MATH_COS(angle/2);
rot.y = axis.x*sinang;
rot.z = axis.y*sinang;
rot.w = axis.z*sinang;
T fnorm = rot.lengthsqr4();
MATH_ASSERT( fnorm > 0.99f && fnorm < 1.01f );
return *this;
}
/// \brief Returns a camera matrix that looks along a ray with a desired up vector. /// \brief Returns a camera matrix that looks along a ray with a desired up vector.
/// ///
/// \ingroup affine_math /// \ingroup affine_math
/// \param[in] vlookat the point space to look at, the camera will rotation and zoom around this point /// \param[in] vlookat the point space to look at, the camera will rotation and zoom around this point
/// \param[in] vcampos the position of the camera in space /// \param[in] vcampos the position of the camera in space
/// \param[in] vcamup vector from the camera /// \param[in] vcamup vector from the camera
template<typename T> template<typename T>
RaveTransformMatrix<T> transformLookat(const RaveVector<T>& vlookat, const RaveVector<T>& vcamerapos, const RaveVector<T>& vcameraup) RaveTransformMatrix<T> transformLookat(const RaveVector<T>& vlookat, const RaveVector<T>& vcamerapos, const RaveVector<T>& vcameraup)
{ {
RaveVector<T> dir = vlookat - vcamerapos; RaveVector<T> dir = vlookat - vcamerapos;
 End of changes. 6 change blocks. 
44 lines changed or deleted 40 lines changed or added


 iksolver.h   iksolver.h 
skipping to change at line 78 skipping to change at line 78
/// For example, some ik solvers might have different ways of computing optimal solutions. /// For example, some ik solvers might have different ways of computing optimal solutions.
/// \param pmanip The manipulator the IK solver is attached to /// \param pmanip The manipulator the IK solver is attached to
virtual bool Init(RobotBase::ManipulatorPtr pmanip) = 0; virtual bool Init(RobotBase::ManipulatorPtr pmanip) = 0;
virtual RobotBase::ManipulatorPtr GetManipulator() const = 0; virtual RobotBase::ManipulatorPtr GetManipulator() const = 0;
/// \brief Sets an ik solution filter that is called for every ik solut ion. /// \brief Sets an ik solution filter that is called for every ik solut ion.
/// ///
/// \param filterfn - an optional filter function to be called, see \re f IkFilterCallbackFn. /// \param filterfn - an optional filter function to be called, see \re f IkFilterCallbackFn.
/// \exception openrave_exception Throw if filters are not supported. /// \exception openrave_exception Throw if filters are not supported.
virtual void SetCustomFilter(const IkFilterCallbackFn& filterfn) { thro w openrave_exception("ik filters ignored",ORE_NotImplemented); } virtual void SetCustomFilter(const IkFilterCallbackFn& filterfn) OPENRA VE_DUMMY_IMPLEMENTATION;
/// \brief Number of free parameters defining the null solution space. /// \brief Number of free parameters defining the null solution space.
/// ///
/// Each parameter is always in the range of [0,1]. /// Each parameter is always in the range of [0,1].
virtual int GetNumFreeParameters() const = 0; virtual int GetNumFreeParameters() const = 0;
/// \brief gets the free parameters from the current robot configuratio n /// \brief gets the free parameters from the current robot configuratio n
/// ///
/// \param[out] vFreeParameters is filled with GetNumFreeParameters() p arameters in [0,1] range /// \param[out] vFreeParameters is filled with GetNumFreeParameters() p arameters in [0,1] range
/// \return true if succeeded /// \return true if succeeded
skipping to change at line 132 skipping to change at line 132
/// Can specify the free parameters in [0,1] range. If NULL, the regula r equivalent Solve is called /// Can specify the free parameters in [0,1] range. If NULL, the regula r equivalent Solve is called
/// \param[in] param the pose the end effector has to achieve. Note tha t the end effector pose /// \param[in] param the pose the end effector has to achieve. Note tha t the end effector pose
/// takes into account the grasp coordinate fram e for the RobotBase::Manipulator /// takes into account the grasp coordinate fram e for the RobotBase::Manipulator
/// \param[in] vFreeParameters The free parameters of the null space of the IK solutions. Always in range of [0,1] /// \param[in] vFreeParameters The free parameters of the null space of the IK solutions. Always in range of [0,1]
/// \param[in] filteroptions A bitmask of \ref IkFilterOptions values c ontrolling what is checked for each ik solution. /// \param[in] filteroptions A bitmask of \ref IkFilterOptions values c ontrolling what is checked for each ik solution.
/// \param[out] solutions All solutions within a reasonable discretizat ion level of the free parameters. /// \param[out] solutions All solutions within a reasonable discretizat ion level of the free parameters.
/// \return true at least one solution is found /// \return true at least one solution is found
virtual bool Solve(const IkParameterization& param, const std::vector<d Real>& vFreeParameters, int filteroptions, std::vector< std::vector<dReal> >& solutions) = 0; virtual bool Solve(const IkParameterization& param, const std::vector<d Real>& vFreeParameters, int filteroptions, std::vector< std::vector<dReal> >& solutions) = 0;
/// \brief returns true if the solver supports a particular ik paramete rization as input. /// \brief returns true if the solver supports a particular ik paramete rization as input.
virtual bool Supports(IkParameterization::Type iktype) const { throw op enrave_exception("IkSolverBase::Supports not implemented",ORE_NotImplemente d); } virtual bool Supports(IkParameterization::Type iktype) const OPENRAVE_D UMMY_IMPLEMENTATION;
private: private:
virtual const char* GetHash() const { return OPENRAVE_IKSOLVER_HASH; } virtual const char* GetHash() const { return OPENRAVE_IKSOLVER_HASH; }
}; };
} // end namespace OpenRAVE } // end namespace OpenRAVE
#endif #endif
 End of changes. 2 change blocks. 
2 lines changed or deleted 2 lines changed or added


 interface.h   interface.h 
skipping to change at line 79 skipping to change at line 79
/// \brief Documentation of the interface in reStructuredText format. S ee \ref writing_plugins_doc. /// \brief Documentation of the interface in reStructuredText format. S ee \ref writing_plugins_doc.
virtual const std::string& GetDescription() const { return __descriptio n; }; virtual const std::string& GetDescription() const { return __descriptio n; };
/// \brief set user data /// \brief set user data
virtual void SetUserData(UserDataPtr data) { __pUserData = data; } virtual void SetUserData(UserDataPtr data) { __pUserData = data; }
/// \deprecated /// \deprecated
virtual void SetUserData(boost::shared_ptr<void> data) RAVE_DEPRECATED { __pUserData = boost::static_pointer_cast<UserData>(data); } virtual void SetUserData(boost::shared_ptr<void> data) RAVE_DEPRECATED { __pUserData = boost::static_pointer_cast<UserData>(data); }
/// \brief return the user custom data /// \brief return the user custom data
virtual UserDataPtr GetUserData() const { return __pUserData; } virtual UserDataPtr GetUserData() const { return __pUserData; }
/// \return the XML filename used to load the interface (sometimes this /// \brief the URI used to load the interface (sometimes this is not po
is not possible if the definition lies inside an environment file). ssible if the definition lies inside an environment file).
virtual const std::string& GetXMLFilename() const { return __strxmlfile virtual const std::string& GetURI() const { return __struri; }
name; } virtual const std::string& GetXMLFilename() const { return __struri; }
/// \brief Clone the contents of an interface to the current interface. /// \brief Clone the contents of an interface to the current interface.
/// ///
/// \param preference the interface whose information to clone /// \param preference the interface whose information to clone
/// \param cloningoptions mask of CloningOptions /// \param cloningoptions mask of CloningOptions
/// \throw openrave_exception if command doesn't succeed /// \throw openrave_exception if command doesn't succeed
virtual void Clone(InterfaceBaseConstPtr preference, int cloningoptions ); virtual void Clone(InterfaceBaseConstPtr preference, int cloningoptions );
/** \brief Used to send special commands to the interface and receive o utput. /** \brief Used to send special commands to the interface and receive o utput.
skipping to change at line 144 skipping to change at line 145
virtual const char* GetHash() const = 0; virtual const char* GetHash() const = 0;
std::string __description; /// \see GetDescription() std::string __description; /// \see GetDescription()
private: private:
/// Write the help commands to an output stream /// Write the help commands to an output stream
virtual bool _GetCommandHelp(std::ostream& sout, std::istream& sinput) const; virtual bool _GetCommandHelp(std::ostream& sout, std::istream& sinput) const;
mutable boost::mutex _mutexInterface; ///< internal mutex for protectin g data from methods that might be access from any thread (those methods sho uld be commented). mutable boost::mutex _mutexInterface; ///< internal mutex for protectin g data from methods that might be access from any thread (those methods sho uld be commented).
InterfaceType __type; ///< \see GetInterfaceType InterfaceType __type; ///< \see GetInterfaceType
boost::shared_ptr<void> __plugin; ///< handle to plugin that controls t he executable code. As long as this plugin pointer is present, module will not be unloaded. boost::shared_ptr<void> __plugin; ///< handle to plugin that controls t he executable code. As long as this plugin pointer is present, module will not be unloaded.
std::string __strxmlfilename; ///< \see GetXMLFilename std::string __struri; ///< \see GetURI
std::string __strpluginname; ///< the name of the plugin, necessary? std::string __strpluginname; ///< the name of the plugin, necessary?
std::string __strxmlid; ///< \see GetXMLId std::string __strxmlid; ///< \see GetXMLId
EnvironmentBasePtr __penv; ///< \see GetEnv EnvironmentBasePtr __penv; ///< \see GetEnv
UserDataPtr __pUserData; ///< \see GetUserData UserDataPtr __pUserData; ///< \see GetUserData
READERSMAP __mapReadableInterfaces; ///< pointers to extra interfaces t hat are included with this object READERSMAP __mapReadableInterfaces; ///< pointers to extra interfaces t hat are included with this object
typedef std::map<std::string, boost::shared_ptr<InterfaceCommand>, Case InsensitiveCompare> CMDMAP; typedef std::map<std::string, boost::shared_ptr<InterfaceCommand>, Case InsensitiveCompare> CMDMAP;
CMDMAP __mapCommands; ///< all registered commands CMDMAP __mapCommands; ///< all registered commands
#ifdef RAVE_PRIVATE #ifdef RAVE_PRIVATE
 End of changes. 2 change blocks. 
5 lines changed or deleted 5 lines changed or added


 interfacehashes.h   interfacehashes.h 
#define OPENRAVE_COLLISIONCHECKER_HASH "014ee35eee66baf7d21e90bf2137403a" #define OPENRAVE_COLLISIONCHECKER_HASH "f0e1d66efd6b80e851a12a937f60eca6"
#define OPENRAVE_ROBOT_HASH "9eb74a9517edd027133a655746c4a7b9" #define OPENRAVE_ROBOT_HASH "bee29611dc861971dc759376933d69cf"
#define OPENRAVE_PLANNER_HASH "2d704018a95c63bacb15b489a016f549" #define OPENRAVE_PLANNER_HASH "7b8864032c6bf5c572e0535c9c164fd4"
#define OPENRAVE_KINBODY_HASH "3578ab77ac5d07679dc3ff9b0b7bef91" #define OPENRAVE_KINBODY_HASH "2d1499ecb721b3af313da4c26b836ce2"
#define OPENRAVE_SENSORSYSTEM_HASH "eb1d5470772bd05aeae6f2263cfc4a32" #define OPENRAVE_SENSORSYSTEM_HASH "43920009ad109091d7e59157a5af3a24"
#define OPENRAVE_CONTROLLER_HASH "f2ccd3f7cb7dbb87c76d4a578025e77d" #define OPENRAVE_CONTROLLER_HASH "3ff86056459c72cbdb34af28b98f0992"
#define OPENRAVE_PROBLEM_HASH "1b9f13107e2369a2e57f0d4a1da05514" #define OPENRAVE_MODULE_HASH "91a6adfcb28019207938af3fbbf759b3"
#define OPENRAVE_IKSOLVER_HASH "b53e988c774f012e265b6f5b00740122" #define OPENRAVE_IKSOLVER_HASH "721e42b775ddd137a81e53f69519d1d9"
#define OPENRAVE_PHYSICSENGINE_HASH "3e8e6df1024f812c66157d581cc1e8cd" #define OPENRAVE_PHYSICSENGINE_HASH "31b1aa40bf4c5b63aa57c5552bf62d81"
#define OPENRAVE_SENSOR_HASH "0a1b8b894aa820aa0fab3397acad643c" #define OPENRAVE_SENSOR_HASH "c7227d59d84d6ad880ea5ae166cc087a"
#define OPENRAVE_VIEWER_HASH "ebf2e8d9edf9b100530e041c3ee70300" #define OPENRAVE_TRAJECTORY_HASH "260138467755d029a252ef128993907e"
#define OPENRAVE_TRAJECTORY_HASH "d1234f4cd37ab79670ac64edfb61dab5" #define OPENRAVE_VIEWER_HASH "81042bd863f0e42be9a5b96fcc912db3"
#define OPENRAVE_ENVIRONMENT_HASH "dce2f6f3be824974d0ca247b985e7f49" #define OPENRAVE_SPACESAMPLER_HASH "8d3866c955b9587aaf42e277edd2da2a"
#define OPENRAVE_PLUGININFO_HASH "50aa022a8e5d67f6b758bfb5e546de78" #define OPENRAVE_ENVIRONMENT_HASH "f29fda952d7a5cef7b8b46a7e4f70a27"
#define OPENRAVE_PLUGININFO_HASH "202a84af5eb50775aa5da86956de73fe"
 End of changes. 1 change blocks. 
lines changed or deleted lines changed or added


 kinbody.h   kinbody.h 
skipping to change at line 28 skipping to change at line 28
\brief Kinematics body related definitions. \brief Kinematics body related definitions.
*/ */
#ifndef OPENRAVE_KINBODY_H #ifndef OPENRAVE_KINBODY_H
#define OPENRAVE_KINBODY_H #define OPENRAVE_KINBODY_H
/// declare function parser class from fparser library /// declare function parser class from fparser library
template<typename Value_t> class FunctionParserBase; template<typename Value_t> class FunctionParserBase;
namespace OpenRAVE { namespace OpenRAVE {
/** \brief <b>[interface]</b> A kinematic body of links and joints. See \re f arch_kinbody. /** \brief <b>[interface]</b> A kinematic body of links and joints. <b>Meth ods not multi-thread safe.</b> See \ref arch_kinbody.
\ingroup interfaces \ingroup interfaces
*/ */
class OPENRAVE_API KinBody : public InterfaceBase class OPENRAVE_API KinBody : public InterfaceBase
{ {
public: public:
/// \brief A set of properties for the kinbody. These properties are us ed to describe a set of variables used in KinBody. /// \brief A set of properties for the kinbody. These properties are us ed to describe a set of variables used in KinBody.
enum KinBodyProperty { enum KinBodyProperty {
Prop_Joints=0x1, ///< all properties of all joints Prop_Joints=0x1, ///< all properties of all joints
Prop_JointLimits=0x2, Prop_JointLimits=0x2|Prop_Joints, ///< regular limits
Prop_JointOffset=0x4, Prop_JointOffset=0x4|Prop_Joints,
Prop_JointProperties=0x8, ///< max velocity, max acceleration, reso Prop_JointProperties=0x8|Prop_Joints, ///< max velocity, max accele
lution, max torque ration, resolution, max torque
Prop_Links=0x10, ///< all properties of all links Prop_Links=0x10, ///< all properties of all links
Prop_Name=0x20, ///< name changed Prop_Name=0x20, ///< name changed
Prop_LinkDraw=0x40, ///< toggle link geometries rendering Prop_LinkDraw=0x40, ///< toggle link geometries rendering
Prop_LinkGeometry=0x80, ///< the geometry of the link changed Prop_LinkGeometry=0x80|Prop_Links, ///< the geometry of the link ch
Prop_JointMimic=0x100, ///< joint mimic equations anged
Prop_JointMimic=0x100|Prop_Joints, ///< joint mimic equations
Prop_JointVelocityLimits=0x200|Prop_Joints, ///< velocity limits
Prop_LinkStatic=0x400|Prop_Links, ///< static property of link chan
ged
// robot only // robot only
Prop_Manipulators = 0x00010000, ///< [robot only] all properties of Prop_RobotManipulators = 0x00010000, ///< [robot only] all properti
all manipulators es of all manipulators
Prop_Sensors = 0x00020000, ///< [robot only] all properties of all Prop_Manipulators = 0x00010000,
sensors Prop_RobotSensors = 0x00020000, ///< [robot only] all properties of
Prop_SensorPlacement = 0x00040000, ///< [robot only] relative senso all sensors
r placement of sensors Prop_Sensors = 0x00020000,
Prop_RobotSensorPlacement = 0x00040000, ///< [robot only] relative
sensor placement of sensors
Prop_SensorPlacement = 0x00040000,
Prop_RobotActiveDOFs = 0x00080000, ///< [robot only] active dofs ch
anged
}; };
/// \brief A rigid body holding all its collision and rendering data. /// \brief A rigid body holding all its collision and rendering data.
class OPENRAVE_API Link : public boost::enable_shared_from_this<Link> class OPENRAVE_API Link : public boost::enable_shared_from_this<Link>
{ {
public: public:
Link(KinBodyPtr parent); ///< pass in a ODE world Link(KinBodyPtr parent); ///< pass in a ODE world
virtual ~Link(); virtual ~Link();
/// \brief User data for trimesh geometries. Vertices are defined i n counter-clockwise order for outward pointing faces. /// \brief User data for trimesh geometries. Vertices are defined i n counter-clockwise order for outward pointing faces.
skipping to change at line 100 skipping to change at line 106
GeomTrimesh = 4, GeomTrimesh = 4,
}; };
GEOMPROPERTIES(boost::shared_ptr<Link> parent); GEOMPROPERTIES(boost::shared_ptr<Link> parent);
virtual ~GEOMPROPERTIES() {} virtual ~GEOMPROPERTIES() {}
/// \brief Local transformation of the geom primitive with resp ect to the link's coordinate system. /// \brief Local transformation of the geom primitive with resp ect to the link's coordinate system.
inline const Transform& GetTransform() const { return _t; } inline const Transform& GetTransform() const { return _t; }
inline GeomType GetType() const { return _type; } inline GeomType GetType() const { return _type; }
inline const Vector& GetRenderScale() const { return vRenderSca le; } inline const Vector& GetRenderScale() const { return vRenderSca le; }
inline const std::string& GetRenderFilename() const { return re nderfile; } inline const std::string& GetRenderFilename() const { return _r enderfilename; }
inline float GetTransparency() const { return ftransparency; } inline float GetTransparency() const { return ftransparency; }
inline bool IsDraw() const { return _bDraw; } inline bool IsDraw() const { return _bDraw; }
inline bool IsModifiable() const { return _bModifiable; } inline bool IsModifiable() const { return _bModifiable; }
inline dReal GetSphereRadius() const { return vGeomData.x; } inline dReal GetSphereRadius() const { return vGeomData.x; }
inline dReal GetCylinderRadius() const { return vGeomData.x; } inline dReal GetCylinderRadius() const { return vGeomData.x; }
inline dReal GetCylinderHeight() const { return vGeomData.y; } inline dReal GetCylinderHeight() const { return vGeomData.y; }
inline const Vector& GetBoxExtents() const { return vGeomData; } inline const Vector& GetBoxExtents() const { return vGeomData; }
inline const RaveVector<float>& GetDiffuseColor() const { retur n diffuseColor; } inline const RaveVector<float>& GetDiffuseColor() const { retur n diffuseColor; }
inline const RaveVector<float>& GetAmbientColor() const { retur n ambientColor; } inline const RaveVector<float>& GetAmbientColor() const { retur n ambientColor; }
/// \brief collision data of the specific object in its local c oordinate system. /// \brief collision data of the specific object in its local c oordinate system.
/// ///
/// Should be transformed by \ref GEOMPROPERTIES::GetTransform( ) before rendering. /// Should be transformed by \ref GEOMPROPERTIES::GetTransform( ) before rendering.
/// For spheres and cylinders, an appropriate discretization va lue is chosen. /// For spheres and cylinders, an appropriate discretization va lue is chosen.
inline const TRIMESH& GetCollisionMesh() const { return collisi onmesh; } inline const TRIMESH& GetCollisionMesh() const { return collisi onmesh; }
virtual AABB ComputeAABB(const Transform& t) const; /// \brief returns an axis aligned bounding box given that the
geometry is transformed by trans
virtual AABB ComputeAABB(const Transform& trans) const;
virtual void serialize(std::ostream& o, int options) const; virtual void serialize(std::ostream& o, int options) const;
/// \brief sets a new collision mesh and notifies every registe red callback about it /// \brief sets a new collision mesh and notifies every registe red callback about it
virtual void SetCollisionMesh(const TRIMESH& mesh); virtual void SetCollisionMesh(const TRIMESH& mesh);
/// \brief sets a drawing and notifies every registered callbac k about it /// \brief sets a drawing and notifies every registered callbac k about it
virtual void SetDraw(bool bDraw); virtual void SetDraw(bool bDraw);
/// \brief set transparency level (0 is opaque) /// \brief set transparency level (0 is opaque)
virtual void SetTransparency(float f); virtual void SetTransparency(float f);
/// \brief override diffuse color of geometry material /// \brief override diffuse color of geometry material
virtual void SetDiffuseColor(const RaveVector<float>& color); virtual void SetDiffuseColor(const RaveVector<float>& color);
/// \brief override ambient color of geometry material /// \brief override ambient color of geometry material
virtual void SetAmbientColor(const RaveVector<float>& color); virtual void SetAmbientColor(const RaveVector<float>& color);
/// validates the contact normal on the surface of the geometry /// \brief validates the contact normal on the surface of the g
and makes sure the normal faces "outside" of the shape. eometry and makes sure the normal faces "outside" of the shape.
///
/// \param position the position of the contact point specified in the link's coordinate system /// \param position the position of the contact point specified in the link's coordinate system
/// \param normal the unit normal of the contact point specifie d in the link's coordinate system /// \param normal the unit normal of the contact point specifie d in the link's coordinate system
/// \return true if the normal is changed to face outside of th e shape /// \return true if the normal is changed to face outside of th e shape
virtual bool ValidateContactNormal(const Vector& position, Vect or& normal) const; virtual bool ValidateContactNormal(const Vector& position, Vect or& normal) const;
/// \brief sets a new render filename for the geometry. This do
es not change the collision
virtual void SetRenderFilename(const std::string& renderfilenam
e);
protected: protected:
/// triangulates the geometry object and initializes collisionm esh. GeomTrimesh types must already be triangulated /// triangulates the geometry object and initializes collisionm esh. GeomTrimesh types must already be triangulated
/// \param fTessellation to control how fine the triangles need to be. 1.0f is the default value /// \param fTessellation to control how fine the triangles need to be. 1.0f is the default value
bool InitCollisionMesh(float fTessellation=1); bool InitCollisionMesh(float fTessellation=1);
boost::weak_ptr<Link> _parent; boost::weak_ptr<Link> _parent;
Transform _t; ///< see \ref GetTransform Transform _t; ///< see \ref GetTransform
Vector vGeomData; ///< for boxes, first 3 values are extents Vector vGeomData; ///< for boxes, first 3 values are extents
///< for sphere it is radius ///< for sphere it is radius
///< for cylinder, first 2 values are radius and height ///< for cylinder, first 2 values are radius and height
///< for trimesh, none ///< for trimesh, none
RaveVector<float> diffuseColor, ambientColor; ///< hints for ho w to color the meshes RaveVector<float> diffuseColor, ambientColor; ///< hints for ho w to color the meshes
TRIMESH collisionmesh; ///< see \ref GetCollisionMesh TRIMESH collisionmesh; ///< see \ref GetCollisionMesh
GeomType _type; ///< the type of geometry primitive GeomType _type; ///< the type of geometry primitive
std::string renderfile; ///< render resource file, should be t ransformed by _t before rendering std::string _renderfilename; ///< render resource file, should be transformed by _t before rendering
Vector vRenderScale; ///< render scale of the object (x,y,z) Vector vRenderScale; ///< render scale of the object (x,y,z)
float ftransparency; ///< value from 0-1 for the transparency o f the rendered object, 0 is opaque float ftransparency; ///< value from 0-1 for the transparency o f the rendered object, 0 is opaque
bool _bDraw; ///< if true, object is drawn as part of t he 3d model (default is true) bool _bDraw; ///< if true, object is drawn as part of t he 3d model (default is true)
bool _bModifiable; ///< if true, object geometry can be dynamic ally modified (default is true) bool _bModifiable; ///< if true, object geometry can be dynamic ally modified (default is true)
#ifdef RAVE_PRIVATE #ifdef RAVE_PRIVATE
#ifdef _MSC_VER #ifdef _MSC_VER
friend class ColladaReader; friend class ColladaReader;
friend class OpenRAVEXMLParser::LinkXMLReader; friend class OpenRAVEXMLParser::LinkXMLReader;
skipping to change at line 180 skipping to change at line 191
friend class KinBody; friend class KinBody;
friend class KinBody::Link; friend class KinBody::Link;
}; };
inline const std::string& GetName() const { return _name; } inline const std::string& GetName() const { return _name; }
/// \brief Indicates a static body that does not move with respect to the root link. /// \brief Indicates a static body that does not move with respect to the root link.
/// ///
//// Static should be used when an object has infinite mass and //// Static should be used when an object has infinite mass and
///< shouldn't be affected by physics (including gravity). Collisio n still works. ///< shouldn't be affected by physics (including gravity). Collisio n still works.
inline bool IsStatic() const { return bStatic; } inline bool IsStatic() const { return _bStatic; }
/// \brief returns true if the link is enabled. \see Enable /// \brief returns true if the link is enabled. \see Enable
virtual bool IsEnabled() const; virtual bool IsEnabled() const;
/// \brief Enables a Link. An enabled link takes part in collision detection and physics simulations /// \brief Enables a Link. An enabled link takes part in collision detection and physics simulations
virtual void Enable(bool enable); virtual void Enable(bool enable);
/// \brief parent body that link belong to. /// \brief parent body that link belong to.
inline KinBodyPtr GetParent() const { return KinBodyPtr(_parent); } inline KinBodyPtr GetParent() const { return KinBodyPtr(_parent); }
/// \brief unique index into parent KinBody::GetLinks vector /// \brief unique index into parent KinBody::GetLinks vector
inline int GetIndex() const { return _index; } inline int GetIndex() const { return _index; }
inline const TRIMESH& GetCollisionData() const { return collision; } inline const TRIMESH& GetCollisionData() const { return collision; }
/// \return the aabb of all the geometries of the link in the world coordinate system /// \brief Compute the aabb of all the geometries of the link in th e world coordinate system
virtual AABB ComputeAABB() const; virtual AABB ComputeAABB() const;
/// \brief Return the current transformation of the link in the wor ld coordinate system. /// \brief Return the current transformation of the link in the wor ld coordinate system.
inline Transform GetTransform() const { return _t; } inline Transform GetTransform() const { return _t; }
/// \brief Return all the direct parent links in the kinematics hie rarchy of this link. /// \brief Return all the direct parent links in the kinematics hie rarchy of this link.
/// ///
/// A parent link is is immediately connected to this link by a joi nt and has a path to the root joint so that it is possible /// A parent link is is immediately connected to this link by a joi nt and has a path to the root joint so that it is possible
/// to compute this link's transformation from its parent. /// to compute this link's transformation from its parent.
/// \param[out] filled with the parent links /// \param[out] filled with the parent links
skipping to change at line 219 skipping to change at line 230
/// ///
/// \see GetParentLinks /// \see GetParentLinks
/// \param link The link to test if it is one of the parents of thi s link. /// \param link The link to test if it is one of the parents of thi s link.
virtual bool IsParentLink(boost::shared_ptr<Link const> plink) cons t; virtual bool IsParentLink(boost::shared_ptr<Link const> plink) cons t;
/// \return center of mass offset in the link's local coordinate fr ame /// \return center of mass offset in the link's local coordinate fr ame
inline Vector GetCOMOffset() const {return _transMass.trans; } inline Vector GetCOMOffset() const {return _transMass.trans; }
inline const TransformMatrix& GetInertia() const { return _transMas s; } inline const TransformMatrix& GetInertia() const { return _transMas s; }
inline dReal GetMass() const { return _mass; } inline dReal GetMass() const { return _mass; }
/// \brief sets a link to be static.
///
/// Because this can affect the kinematics, it requires the body's
internal structures to be recomputed
virtual void SetStatic(bool bStatic);
/// \brief Sets the transform of the link regardless of kinematics
///
/// \param[in] t the new transformation /// \param[in] t the new transformation
virtual void SetTransform(const Transform& transform); virtual void SetTransform(const Transform& transform);
/// adds an external force at pos (absolute coords) /// adds an external force at pos (absolute coords)
/// \param[in] force the direction and magnitude of the force /// \param[in] force the direction and magnitude of the force
/// \param[in] pos in the world where the force is getting applied /// \param[in] pos in the world where the force is getting applied
/// \param[in] add if true, force is added to previous forces, othe rwise it is set /// \param[in] add if true, force is added to previous forces, othe rwise it is set
virtual void SetForce(const Vector& force, const Vector& pos, bool add); virtual void SetForce(const Vector& force, const Vector& pos, bool add);
/// adds torque to a body (absolute coords) /// adds torque to a body (absolute coords)
skipping to change at line 282 skipping to change at line 301
Transform _t; ///< \see GetTransform Transform _t; ///< \see GetTransform
TransformMatrix _transMass; ///< the 3x3 inertia and center of mass of the link in the link's coordinate system TransformMatrix _transMass; ///< the 3x3 inertia and center of mass of the link in the link's coordinate system
dReal _mass; dReal _mass;
TRIMESH collision; ///< triangles for collision checking, triangles are always the triangulation TRIMESH collision; ///< triangles for collision checking, triangles are always the triangulation
///< of the body when it is at the identity tran sformation ///< of the body when it is at the identity tran sformation
std::string _name; ///< optional link name std::string _name; ///< optional link name
std::list<GEOMPROPERTIES> _listGeomProperties; ///< \see GetGeometr ies std::list<GEOMPROPERTIES> _listGeomProperties; ///< \see GetGeometr ies
bool bStatic; ///< \see IsStatic bool _bStatic; ///< \see IsStatic
bool _bIsEnabled; ///< \see IsEnabled bool _bIsEnabled; ///< \see IsEnabled
private: private:
/// Sensitive variables that should not be modified. /// Sensitive variables that should not be modified.
/// @name Private Link Variables /// @name Private Link Variables
//@{ //@{
int _index; ///< \see GetIndex int _index; ///< \see GetIndex
KinBodyWeakPtr _parent; ///< \see GetParent KinBodyWeakPtr _parent; ///< \see GetParent
std::vector<int> _vParentLinks; ///< \see GetParentLinks, IsParentL ink std::vector<int> _vParentLinks; ///< \see GetParentLinks, IsParentL ink
std::vector<int> _vRigidlyAttachedLinks; ///< \see IsRigidlyAttache d, GetRigidlyAttachedLinks std::vector<int> _vRigidlyAttachedLinks; ///< \see IsRigidlyAttache d, GetRigidlyAttachedLinks
skipping to change at line 309 skipping to change at line 328
friend class OpenRAVEXMLParser::RobotXMLReader; friend class OpenRAVEXMLParser::RobotXMLReader;
#else #else
friend class ::ColladaReader; friend class ::ColladaReader;
friend class ::OpenRAVEXMLParser::LinkXMLReader; friend class ::OpenRAVEXMLParser::LinkXMLReader;
friend class ::OpenRAVEXMLParser::KinBodyXMLReader; friend class ::OpenRAVEXMLParser::KinBodyXMLReader;
friend class ::OpenRAVEXMLParser::RobotXMLReader; friend class ::OpenRAVEXMLParser::RobotXMLReader;
#endif #endif
#endif #endif
friend class KinBody; friend class KinBody;
}; };
typedef boost::shared_ptr<Link> LinkPtr; typedef boost::shared_ptr<KinBody::Link> LinkPtr;
typedef boost::shared_ptr<Link const> LinkConstPtr; typedef boost::shared_ptr<KinBody::Link const> LinkConstPtr;
typedef boost::weak_ptr<Link> LinkWeakPtr; typedef boost::weak_ptr<KinBody::Link> LinkWeakPtr;
/// \brief Information about a joint that controls the relationship bet ween two links. /// \brief Information about a joint that controls the relationship bet ween two links.
class OPENRAVE_API Joint : public boost::enable_shared_from_this<Joint> class OPENRAVE_API Joint : public boost::enable_shared_from_this<Joint>
{ {
public: public:
/** \brief The type of joint movement. /** \brief The type of joint movement.
Non-special joints that are combinations of revolution and pris matic joints. Non-special joints that are combinations of revolution and pris matic joints.
The first 4 bits specify the joint DOF, the next bits specify w hether the joint is revolute (0) or prismatic (1). The first 4 bits specify the joint DOF, the next bits specify w hether the joint is revolute (0) or prismatic (1).
There can be also special joint types that are valid if the Joi ntSpecialBit is set. There can be also special joint types that are valid if the Joi ntSpecialBit is set.
skipping to change at line 347 skipping to change at line 366
JointHinge2 = 0x80000002, JointHinge2 = 0x80000002,
JointSpherical = 0x80000003, JointSpherical = 0x80000003,
}; };
Joint(KinBodyPtr parent); Joint(KinBodyPtr parent);
virtual ~Joint(); virtual ~Joint();
/// \brief The unique name of the joint /// \brief The unique name of the joint
inline const std::string& GetName() const { return _name; } inline const std::string& GetName() const { return _name; }
inline dReal GetMaxVel(int iaxis=0) const { return fMaxVel[iaxis]; inline dReal GetMaxVel(int iaxis=0) const { return _vmaxvel[iaxis];
} }
inline dReal GetMaxAccel(int iaxis=0) const { return fMaxAccel[iaxi inline dReal GetMaxAccel(int iaxis=0) const { return _vmaxaccel[iax
s]; } is]; }
inline dReal GetMaxTorque(int iaxis=0) const { return fMaxTorque[ia inline dReal GetMaxTorque(int iaxis=0) const { return _vmaxtorque[i
xis]; } axis]; }
/// \brief Get the degree of freedom index in the body's DOF array. /// \brief Get the degree of freedom index in the body's DOF array.
/// ///
/// This does not index in KinBody::GetJoints() directly! In other words, KinBody::GetDOFValues()[GetDOFIndex()] == GetValues()[0] /// This does not index in KinBody::GetJoints() directly! In other words, KinBody::GetDOFValues()[GetDOFIndex()] == GetValues()[0]
inline int GetDOFIndex() const { return dofindex; } inline int GetDOFIndex() const { return dofindex; }
/// \brief Get the joint index into KinBody::GetJoints. /// \brief Get the joint index into KinBody::GetJoints.
inline int GetJointIndex() const { return jointindex; } inline int GetJointIndex() const { return jointindex; }
inline KinBodyPtr GetParent() const { return KinBodyPtr(_parent); } inline KinBodyPtr GetParent() const { return KinBodyPtr(_parent); }
skipping to change at line 427 skipping to change at line 446
/// \brief The axis of the joint in global coordinates /// \brief The axis of the joint in global coordinates
/// ///
/// \param[in] axis the axis to get /// \param[in] axis the axis to get
virtual Vector GetAxis(int axis = 0) const; virtual Vector GetAxis(int axis = 0) const;
/** \brief Returns the limits of the joint /** \brief Returns the limits of the joint
\param[out] vLowerLimit the lower limits \param[out] vLowerLimit the lower limits
\param[out] vUpperLimit the upper limits \param[out] vUpperLimit the upper limits
\param[in] bAppend if true will append to the end of the vector instead of erasing it \param[in] bAppend if true will append to the end of the vector instead of erasing it
\return degrees of freedom of the joint
*/ */
virtual void GetLimits(std::vector<dReal>& vLowerLimit, std::vector <dReal>& vUpperLimit, bool bAppend=false) const; virtual void GetLimits(std::vector<dReal>& vLowerLimit, std::vector <dReal>& vUpperLimit, bool bAppend=false) const;
/// \brief \see GetLimits /// \brief \see GetLimits
virtual void SetLimits(const std::vector<dReal>& lower, const std:: vector<dReal>& upper); virtual void SetLimits(const std::vector<dReal>& lower, const std:: vector<dReal>& upper);
/// \deprecated (11/1/1) /// \deprecated (11/1/1)
virtual void SetJointLimits(const std::vector<dReal>& lower, const std::vector<dReal>& upper) RAVE_DEPRECATED { SetLimits(lower,upper); } virtual void SetJointLimits(const std::vector<dReal>& lower, const std::vector<dReal>& upper) RAVE_DEPRECATED { SetLimits(lower,upper); }
virtual void GetVelocityLimits(std::vector<dReal>& vLowerLimit, std /** \brief Returns the max velocities of the joint
::vector<dReal>& vUpperLimit, bool bAppend=false) const;
\param[out] vlower the lower velocity limits
\param[out] vupper the lower velocity limits
\param[in] bAppend if true will append to the end of the vector
instead of erasing it
*/
virtual void GetVelocityLimits(std::vector<dReal>& vlower, std::vec
tor<dReal>& vupper, bool bAppend=false) const;
/// \brief \see GetVelocityLimits
virtual void SetVelocityLimits(const std::vector<dReal>& vmaxvel);
/// \brief The weight associated with a joint's axis for computing a distance in the robot configuration space. /// \brief The weight associated with a joint's axis for computing a distance in the robot configuration space.
virtual dReal GetWeight(int axis=0) const; virtual dReal GetWeight(int axis=0) const;
/// \brief \see GetWeight /// \brief \see GetWeight
virtual void SetWeights(const std::vector<dReal>& weights); virtual void SetWeights(const std::vector<dReal>& weights);
/// \brief Return internal offset parameter that determines the zer o of the joint offset. /// \brief Return internal offset parameter that determines the bra nch the angle centers on
/// ///
/// Offsets are needed for rotation joints since the range is limit /// Wrap offsets are needed for rotation joints since the range is
ed to 2*pi. limited to 2*pi.
/// This allows the offset to be set so the joint can function in [ /// This allows the wrap offset to be set so the joint can function
-pi+offset,pi+offset].. in [-pi+offset,pi+offset]..
/// \param iaxis the axis to get the offset from /// \param iaxis the axis to get the offset from
inline dReal GetOffset(int iaxis=0) const { return _offsets.at(iaxi inline dReal GetWrapOffset(int iaxis=0) const { return _voffsets.at
s); } (iaxis); }
/// \brief \see GetOffset
virtual void SetOffset(dReal offset, int iaxis=0); inline dReal GetOffset(int iaxis=0) const RAVE_DEPRECATED { return
GetWrapOffset(iaxis); }
/// \brief \see GetWrapOffset
virtual void SetWrapOffset(dReal offset, int iaxis=0);
/// \deprecated (11/1/16) /// \deprecated (11/1/16)
virtual void SetJointOffset(dReal offset, int iaxis=0) RAVE_DEPRECA TED { SetOffset(offset,iaxis); } virtual void SetOffset(dReal offset, int iaxis=0) RAVE_DEPRECATED { SetWrapOffset(offset,iaxis); }
virtual void serialize(std::ostream& o, int options) const; virtual void serialize(std::ostream& o, int options) const;
/// @name Internal Hierarchy Methods /// @name Internal Hierarchy Methods
//@{ //@{
/// \brief Return the parent link which the joint measures its angl e off from (either GetFirstAttached() or GetSecondAttached()) /// \brief Return the parent link which the joint measures its angl e off from (either GetFirstAttached() or GetSecondAttached())
virtual LinkPtr GetHierarchyParentLink() const; virtual LinkPtr GetHierarchyParentLink() const;
/// \brief Return the child link whose transformation is computed b y this joint's values (either GetFirstAttached() or GetSecondAttached()) /// \brief Return the child link whose transformation is computed b y this joint's values (either GetFirstAttached() or GetSecondAttached())
virtual LinkPtr GetHierarchyChildLink() const; virtual LinkPtr GetHierarchyChildLink() const;
/// \deprecated (11/1/27) /// \deprecated (11/1/27)
skipping to change at line 529 skipping to change at line 561
\param[in] axis the axis to set the properties for. \param[in] axis the axis to set the properties for.
\param[in] poseq Equation for joint's position. If it is empty, the mimic properties are turned off for this joint. \param[in] poseq Equation for joint's position. If it is empty, the mimic properties are turned off for this joint.
\param[in] veleq First-order partial derivatives of poseq with respect to all used DOFs. Only the variables used in poseq are allowed to b e used. If poseq is not empty, this is required. \param[in] veleq First-order partial derivatives of poseq with respect to all used DOFs. Only the variables used in poseq are allowed to b e used. If poseq is not empty, this is required.
\param[in] acceleq Second-order partial derivatives of poseq wi th respect to all used DOFs. Only the variables used in poseq are allowed t o be used. Optional. \param[in] acceleq Second-order partial derivatives of poseq wi th respect to all used DOFs. Only the variables used in poseq are allowed t o be used. Optional.
\throw openrave_exception Throws an exception if the mimic equa tion is invalid in any way. \throw openrave_exception Throws an exception if the mimic equa tion is invalid in any way.
*/ */
void SetMimicEquations(int axis, const std::string& poseq, const st d::string& veleq, const std::string& acceleq=""); void SetMimicEquations(int axis, const std::string& poseq, const st d::string& veleq, const std::string& acceleq="");
//@} //@}
protected: protected:
boost::array<Vector,3> vAxes; ///< axes in body[0]'s or envi ronment coordinate system used to define joint movement boost::array<Vector,3> _vaxes; ///< axes in body[0]'s or env ironment coordinate system used to define joint movement
Vector vanchor; ///< anchor of the joint, this is only used to construct the internal left/right matrices Vector vanchor; ///< anchor of the joint, this is only used to construct the internal left/right matrices
dReal fResolution; ///< interpolation resolution dReal fResolution; ///< interpolation resolution
boost::array<dReal,3> fMaxVel; ///< the soft maximum veloc ity (rad/s) to move the joint when planning boost::array<dReal,3> _vmaxvel; ///< the soft maximum velo city (rad/s) to move the joint when planning
boost::array<dReal,3> fHardMaxVel; ///< the hard maximum veloc ity, robot cannot exceed this velocity. used for verification checking boost::array<dReal,3> fHardMaxVel; ///< the hard maximum veloc ity, robot cannot exceed this velocity. used for verification checking
boost::array<dReal,3> fMaxAccel; ///< the maximum accelerati boost::array<dReal,3> _vmaxaccel; ///< the maximum accelerat
on (rad/s^2) of the joint ion (rad/s^2) of the joint
boost::array<dReal,3> fMaxTorque; ///< maximum torque (N.m, k boost::array<dReal,3> _vmaxtorque; ///< maximum torque (N.m,
g m^2/s^2) that can be applied to the joint kg m^2/s^2) that can be applied to the joint
std::vector<dReal> _vweights; ///< the weights of the joint boost::array<dReal,3> _vweights; ///< the weights of the joi
for computing distance metrics. nt for computing distance metrics.
boost::array<dReal,3> _offsets; ///< \see GetOffset boost::array<dReal,3> _voffsets; ///< \see GetOffset
std::vector<dReal> _vlowerlimit, _vupperlimit; ///< joint limits boost::array<dReal,3> _vlowerlimit, _vupperlimit; ///< joint limits
/// \brief Holds mimic information about position, velocity, and ac celeration of one axis of the joint. /// \brief Holds mimic information about position, velocity, and ac celeration of one axis of the joint.
/// ///
/// In every array, [0] is position, [1] is velocity, [2] is accele ration. /// In every array, [0] is position, [1] is velocity, [2] is accele ration.
struct OPENRAVE_API MIMIC struct OPENRAVE_API MIMIC
{ {
struct DOFFormat struct DOFFormat
{ {
int16_t jointindex; ///< the index into the joints, if >= G etJoints.size(), then points to the passive joints int16_t jointindex; ///< the index into the joints, if >= G etJoints.size(), then points to the passive joints
int16_t dofindex : 14; ///< if >= 0, then points to a DOF o f the robot that is NOT mimiced int16_t dofindex : 14; ///< if >= 0, then points to a DOF o f the robot that is NOT mimiced
uint8_t axis : 2; ///< the axis of the joint index uint8_t axis : 2; ///< the axis of the joint index
skipping to change at line 579 skipping to change at line 611
If the joint is not mimic, then just returns its own index If the joint is not mimic, then just returns its own index
\param[out] vpartials A list of dofindex/velocity_partial pairs . The final velocity is computed by taking the dot product. The dofindices do not repeat. \param[out] vpartials A list of dofindex/velocity_partial pairs . The final velocity is computed by taking the dot product. The dofindices do not repeat.
\param[in] iaxis the axis \param[in] iaxis the axis
\param[in,out] vcachedpartials set of cached partials for each degree of freedom \param[in,out] vcachedpartials set of cached partials for each degree of freedom
*/ */
virtual void _ComputePartialVelocities(std::vector<std::pair<int,dR eal> >& vpartials, int iaxis, std::map< std::pair<MIMIC::DOFFormat, int>, d Real >& mapcachedpartials) const; virtual void _ComputePartialVelocities(std::vector<std::pair<int,dR eal> >& vpartials, int iaxis, std::map< std::pair<MIMIC::DOFFormat, int>, d Real >& mapcachedpartials) const;
/** \brief Compute internal transformations and specify the attache d links of the joint. /** \brief Compute internal transformations and specify the attache d links of the joint.
Called after the joint protected parameters {vAxes, vanchor, an d _offsets} have been initialized. vAxes and vanchor should be in the fram e of plink0. Called after the joint protected parameters {vAxes, vanchor, an d _voffsets} have been initialized. vAxes and vanchor should be in the fra me of plink0.
Compute the left and right multiplications of the joint transfo rmation and cleans up the attached bodies. Compute the left and right multiplications of the joint transfo rmation and cleans up the attached bodies.
After function completes, the following parameters are initiali zed: _tRight, _tLeft, _tinvRight, _tinvLeft, _attachedbodies. _attachedbodi es does not necessarily contain the links in the same order as they were in put. After function completes, the following parameters are initiali zed: _tRight, _tLeft, _tinvRight, _tinvLeft, _attachedbodies. _attachedbodi es does not necessarily contain the links in the same order as they were in put.
\param plink0 the first attaching link, all axes and anchors ar e defined in its coordinate system \param plink0 the first attaching link, all axes and anchors ar e defined in its coordinate system
\param plink1 the second attaching link \param plink1 the second attaching link
\param the anchor of the rotation axes \param vanchor the anchor of the rotation axes
\param vaxes the axes in plink0's coordinate system of the join
ts
\param vinitialvalues the current values of the robot used to s
et the 0 offset of the robot
*/ */
virtual void _ComputeInternalInformation(LinkPtr plink0, LinkPtr pl ink1, const Vector& vanchor); virtual void _ComputeInternalInformation(LinkPtr plink0, LinkPtr pl ink1, const Vector& vanchor, const std::vector<Vector>& vaxes, const std::v ector<dReal>& vcurrentvalues);
std::string _name; ///< \see GetName std::string _name; ///< \see GetName
boost::array<bool,3> _bIsCircular; ///< \see IsCircular boost::array<bool,3> _bIsCircular; ///< \see IsCircular
private: private:
/// Sensitive variables that should not be modified. /// Sensitive variables that should not be modified.
/// @name Private Joint Variables /// @name Private Joint Variables
//@{ //@{
int dofindex; ///< the degree of freedom index in the bod y's DOF array, does not index in KinBody::_vecjoints! int dofindex; ///< the degree of freedom index in the bod y's DOF array, does not index in KinBody::_vecjoints!
int jointindex; ///< the joint index into KinBody::_vecjoin ts int jointindex; ///< the joint index into KinBody::_vecjoin ts
JointType _type; JointType _type;
skipping to change at line 623 skipping to change at line 657
#else #else
friend class ::ColladaReader; friend class ::ColladaReader;
friend class ::ColladaWriter; friend class ::ColladaWriter;
friend class ::OpenRAVEXMLParser::JointXMLReader; friend class ::OpenRAVEXMLParser::JointXMLReader;
friend class ::OpenRAVEXMLParser::KinBodyXMLReader; friend class ::OpenRAVEXMLParser::KinBodyXMLReader;
friend class ::OpenRAVEXMLParser::RobotXMLReader; friend class ::OpenRAVEXMLParser::RobotXMLReader;
#endif #endif
#endif #endif
friend class KinBody; friend class KinBody;
}; };
typedef boost::shared_ptr<Joint> JointPtr; typedef boost::shared_ptr<KinBody::Joint> JointPtr;
typedef boost::shared_ptr<Joint const> JointConstPtr; typedef boost::shared_ptr<KinBody::Joint const> JointConstPtr;
typedef boost::weak_ptr<Joint> JointWeakPtr; typedef boost::weak_ptr<KinBody::Joint> JointWeakPtr;
/// \brief Stores the state of the current body that is published in a thread safe way from the environment without requiring locking the environm ent. /// \brief Stores the state of the current body that is published in a thread safe way from the environment without requiring locking the environm ent.
class BodyState class BodyState
{ {
public: public:
BodyState() : environmentid(0){} BodyState() : environmentid(0){}
virtual ~BodyState() {} virtual ~BodyState() {}
KinBodyPtr pbody; KinBodyPtr pbody;
std::vector<RaveTransform<dReal> > vectrans; std::vector<RaveTransform<dReal> > vectrans;
std::vector<dReal> jointvalues; std::vector<dReal> jointvalues;
UserDataPtr pguidata, puserdata; UserDataPtr pguidata, puserdata;
std::string strname; ///< name of the body std::string strname; ///< name of the body
int environmentid; int environmentid;
}; };
typedef boost::shared_ptr<BodyState> BodyStatePtr; typedef boost::shared_ptr<KinBody::BodyState> BodyStatePtr;
typedef boost::shared_ptr<BodyState const> BodyStateConstPtr; typedef boost::shared_ptr<KinBody::BodyState const> BodyStateConstPtr;
/// \brief Access point of the sensor system that manages the body. /// \brief Access point of the sensor system that manages the body.
class OPENRAVE_API ManageData : public boost::enable_shared_from_this<M anageData> class OPENRAVE_API ManageData : public boost::enable_shared_from_this<M anageData>
{ {
public: public:
ManageData(SensorSystemBasePtr psensorsystem) : _psensorsystem(psensors ystem) {} ManageData(SensorSystemBasePtr psensorsystem) : _psensorsystem(psensors ystem) {}
virtual ~ManageData() {} virtual ~ManageData() {}
virtual SensorSystemBasePtr GetSystem() { return SensorSystemBasePt r(_psensorsystem); } virtual SensorSystemBasePtr GetSystem() { return SensorSystemBasePt r(_psensorsystem); }
skipping to change at line 679 skipping to change at line 713
/// set a lock on a particular body /// set a lock on a particular body
virtual bool Lock(bool bDoLock) = 0; virtual bool Lock(bool bDoLock) = 0;
private: private:
/// the system that owns this class, note that it is a weak pointer in order because /// the system that owns this class, note that it is a weak pointer in order because
/// this object is managed by the sensor system and should be delet ed when it goes out of scope. /// this object is managed by the sensor system and should be delet ed when it goes out of scope.
SensorSystemBaseWeakPtr _psensorsystem; SensorSystemBaseWeakPtr _psensorsystem;
}; };
typedef boost::shared_ptr<ManageData> ManageDataPtr; typedef boost::shared_ptr<KinBody::ManageData> ManageDataPtr;
typedef boost::shared_ptr<ManageData const> ManageDataConstPtr; typedef boost::shared_ptr<KinBody::ManageData const> ManageDataConstPtr
;
/// \brief Parameters passed into the state savers to control what info rmation gets saved. /// \brief Parameters passed into the state savers to control what info rmation gets saved.
enum SaveParameters enum SaveParameters
{ {
Save_LinkTransformation=0x00000001, ///< save link transformations Save_LinkTransformation=0x00000001, ///< [default] save link transf
Save_LinkEnable=0x00000002, ///< save link enable states ormations
// robot only Save_LinkEnable=0x00000002, ///< [default] save link enable states
Save_LinkVelocities=0x00000004, ///< save the link velocities
Save_ActiveDOF=0x00010000, ///< [robot only], saves and restores th e current active degrees of freedom Save_ActiveDOF=0x00010000, ///< [robot only], saves and restores th e current active degrees of freedom
Save_ActiveManipulator=0x00020000, ///< [robot only], saves the act ive manipulator Save_ActiveManipulator=0x00020000, ///< [robot only], saves the act ive manipulator
Save_GrabbedBodies=0x00040000, ///< [robot only], saves the grabbed state of the bodies. This does not affect the configuraiton of those bodie s. Save_GrabbedBodies=0x00040000, ///< [robot only], saves the grabbed state of the bodies. This does not affect the configuraiton of those bodie s.
}; };
/// \brief Helper class to save and restore the entire kinbody state. /// \brief Helper class to save and restore the entire kinbody state.
/// ///
/// Options can be passed to the constructor in order to choose which p arameters to save (see \ref SaveParameters) /// Options can be passed to the constructor in order to choose which p arameters to save (see \ref SaveParameters)
class OPENRAVE_API KinBodyStateSaver class OPENRAVE_API KinBodyStateSaver
{ {
public: public:
KinBodyStateSaver(KinBodyPtr pbody, int options = Save_LinkTransfor mation|Save_LinkEnable); KinBodyStateSaver(KinBodyPtr pbody, int options = Save_LinkTransfor mation|Save_LinkEnable);
virtual ~KinBodyStateSaver(); virtual ~KinBodyStateSaver();
protected: protected:
int _options; ///< saved options int _options; ///< saved options
std::vector<Transform> _vLinkTransforms; std::vector<Transform> _vLinkTransforms;
std::vector<uint8_t> _vEnabledLinks; std::vector<uint8_t> _vEnabledLinks;
std::vector<std::pair<Vector,Vector> > _vLinkVelocities;
KinBodyPtr _pbody; KinBodyPtr _pbody;
}; };
virtual ~KinBody(); virtual ~KinBody();
/// return the static interface type this class points to (used for saf e casting) /// return the static interface type this class points to (used for saf e casting)
static inline InterfaceType GetInterfaceTypeStatic() { return PT_KinBod y; } static inline InterfaceType GetInterfaceTypeStatic() { return PT_KinBod y; }
virtual void Destroy(); virtual void Destroy();
skipping to change at line 732 skipping to change at line 767
/// \param vaabbs the array of aligned bounding boxes that will compris e of the body /// \param vaabbs the array of aligned bounding boxes that will compris e of the body
/// \param bDraw if true, the boxes will be rendered in the scene /// \param bDraw if true, the boxes will be rendered in the scene
virtual bool InitFromBoxes(const std::vector<AABB>& boxes, bool draw); virtual bool InitFromBoxes(const std::vector<AABB>& boxes, bool draw);
/// \brief Create a kinbody with one link composed of an array of orien ted bounding boxes. /// \brief Create a kinbody with one link composed of an array of orien ted bounding boxes.
/// ///
/// \param vobbs the array of oriented bounding boxes that will compris e of the body /// \param vobbs the array of oriented bounding boxes that will compris e of the body
/// \param bDraw if true, the boxes will be rendered in the scene /// \param bDraw if true, the boxes will be rendered in the scene
virtual bool InitFromBoxes(const std::vector<OBB>& boxes, bool draw); virtual bool InitFromBoxes(const std::vector<OBB>& boxes, bool draw);
/// \brief Create a kinbody with one link composed of an array of spher
es
///
/// \param vspheres the XYZ position of the spheres with the W coordina
te representing the individual radius
virtual bool InitFromSpheres(const std::vector<Vector>& vspheres, bool
draw);
/// \brief Create a kinbody with one link composed of a triangle mesh s urface /// \brief Create a kinbody with one link composed of a triangle mesh s urface
/// ///
/// \param trimesh the triangle mesh /// \param trimesh the triangle mesh
/// \param bDraw if true, will be rendered in the scene /// \param bDraw if true, will be rendered in the scene
virtual bool InitFromTrimesh(const Link::TRIMESH& trimesh, bool draw); virtual bool InitFromTrimesh(const Link::TRIMESH& trimesh, bool draw);
/// \brief Unique name of the robot. /// \brief Unique name of the robot.
virtual const std::string& GetName() const { return _name; } virtual const std::string& GetName() const { return _name; }
/// \brief Set the name of the robot, notifies the environment and chec ks for uniqueness. /// \brief Set the name of the robot, notifies the environment and chec ks for uniqueness.
virtual void SetName(const std::string& name); virtual void SetName(const std::string& name);
/// Methods for accessing basic information about joints /// Methods for accessing basic information about joints
/// @name Basic Information /// @name Basic Information
//@{ //@{
/// \return number of controllable degrees of freedom of the body. Only /// \brief Number controllable degrees of freedom of the body.
uses _vecjoints and last joint for computation, so can work before Compute ///
JointHierarchy is called. /// Only uses _vecjoints and last joint for computation, so can work be
fore _ComputeInternalInformation is called.
virtual int GetDOF() const; virtual int GetDOF() const;
/// Returns all the joint values as organized by the DOF indices. /// \brief Returns all the joint values as organized by the DOF indices .
virtual void GetDOFValues(std::vector<dReal>& v) const; virtual void GetDOFValues(std::vector<dReal>& v) const;
/// \brief Returns all the joint velocities as organized by the DOF ind ices.
virtual void GetDOFVelocities(std::vector<dReal>& v) const; virtual void GetDOFVelocities(std::vector<dReal>& v) const;
/// \brief Returns all the joint limits as organized by the DOF indices .
virtual void GetDOFLimits(std::vector<dReal>& vLowerLimit, std::vector< dReal>& vUpperLimit) const; virtual void GetDOFLimits(std::vector<dReal>& vLowerLimit, std::vector< dReal>& vUpperLimit) const;
/// \brief Returns all the joint velocity limits as organized by the DO F indices.
virtual void GetDOFVelocityLimits(std::vector<dReal>& vLowerLimit, std: :vector<dReal>& vUpperLimit) const; virtual void GetDOFVelocityLimits(std::vector<dReal>& vLowerLimit, std: :vector<dReal>& vUpperLimit) const;
virtual void GetDOFMaxVel(std::vector<dReal>& v) const; /// \deprecated (11/05/26)
virtual void GetDOFMaxVel(std::vector<dReal>& v) const RAVE_DEPRECATED
{ std::vector<dReal> dummy; GetDOFVelocityLimits(dummy,v); }
virtual void GetDOFMaxAccel(std::vector<dReal>& v) const; virtual void GetDOFMaxAccel(std::vector<dReal>& v) const;
virtual void GetDOFMaxTorque(std::vector<dReal>& v) const; virtual void GetDOFMaxTorque(std::vector<dReal>& v) const;
virtual void GetDOFResolutions(std::vector<dReal>& v) const; virtual void GetDOFResolutions(std::vector<dReal>& v) const;
virtual void GetDOFWeights(std::vector<dReal>& v) const; virtual void GetDOFWeights(std::vector<dReal>& v) const;
/// \deprecated Returns all the joint values in the order of GetJoints( ) (use GetDOFValues instead) (10/07/10) /// \deprecated Returns all the joint values in the order of GetJoints( ) (use GetDOFValues instead) (10/07/10)
virtual void GetJointValues(std::vector<dReal>& v) const RAVE_DEPRECATE virtual void GetJointValues(std::vector<dReal>& v) const RAVE_DEPRECATE
D; D { GetDOFValues(v); }
virtual void GetJointVelocities(std::vector<dReal>& v) const RAVE_DEPRE virtual void GetJointVelocities(std::vector<dReal>& v) const RAVE_DEPRE
CATED; CATED { GetDOFVelocities(v); }
virtual void GetJointLimits(std::vector<dReal>& vLowerLimit, std::vecto virtual void GetJointLimits(std::vector<dReal>& vLowerLimit, std::vecto
r<dReal>& vUpperLimit) const RAVE_DEPRECATED; r<dReal>& vUpperLimit) const RAVE_DEPRECATED { GetDOFLimits(vLowerLimit,vUp
virtual void GetJointMaxVel(std::vector<dReal>& v) const RAVE_DEPRECATE perLimit); }
D; virtual void GetJointMaxVel(std::vector<dReal>& v) const RAVE_DEPRECATE
virtual void GetJointMaxAccel(std::vector<dReal>& v) const RAVE_DEPRECA D { std::vector<dReal> dummy; GetDOFVelocityLimits(dummy,v); }
TED; virtual void GetJointMaxAccel(std::vector<dReal>& v) const RAVE_DEPRECA
virtual void GetJointMaxTorque(std::vector<dReal>& v) const RAVE_DEPREC TED { GetDOFMaxAccel(v); }
ATED; virtual void GetJointMaxTorque(std::vector<dReal>& v) const RAVE_DEPREC
virtual void GetJointResolutions(std::vector<dReal>& v) const RAVE_DEPR ATED { GetDOFMaxTorque(v); }
ECATED; virtual void GetJointResolutions(std::vector<dReal>& v) const RAVE_DEPR
virtual void GetJointWeights(std::vector<dReal>& v) const RAVE_DEPRECAT ECATED { GetDOFResolutions(v); }
ED; virtual void GetJointWeights(std::vector<dReal>& v) const RAVE_DEPRECAT
ED { GetDOFWeights(v); }
/// \brief Returns the joints making up the controllable degrees of fre edom of the body. /// \brief Returns the joints making up the controllable degrees of fre edom of the body.
const std::vector<JointPtr>& GetJoints() const { return _vecjoints; } const std::vector<JointPtr>& GetJoints() const { return _vecjoints; }
/// \brief Returns the passive joints, order does not matter. /** \brief Returns the passive joints, order does not matter.
///
/// A passive joint is not directly controlled by the body's degrees of A passive joint is not directly controlled by the body's degrees of
freedom so it has no freedom so it has no
/// joint index and no dof index. Passive joints allows mimic joints to joint index and no dof index. Passive joints allows mimic joints to
be hidden from the users. be hidden from the users.
However, there are cases when passive joints are not mimic; for exa
mple, suspension mechanism on vehicles.
*/
const std::vector<JointPtr>& GetPassiveJoints() const { return _vPassiv eJoints; } const std::vector<JointPtr>& GetPassiveJoints() const { return _vPassiv eJoints; }
/// \deprecated \see Link::GetRigidlyAttachedLinks (10/12/12) /// \deprecated \see Link::GetRigidlyAttachedLinks (10/12/12)
virtual void GetRigidlyAttachedLinks(int linkindex, std::vector<LinkPtr >& vattachedlinks) const RAVE_DEPRECATED; virtual void GetRigidlyAttachedLinks(int linkindex, std::vector<LinkPtr >& vattachedlinks) const RAVE_DEPRECATED;
/// \brief Returns the joints in hierarchical order starting at the bas e link. /// \brief Returns the joints in hierarchical order starting at the bas e link.
/// ///
/// In the case of closed loops, the joints are returned in the order c losest to the root. /// In the case of closed loops, the joints are returned in the order c losest to the root.
/// All the joints affecting a particular joint's transformation will a lways come before the joint in the list. /// All the joints affecting a particular joint's transformation will a lways come before the joint in the list.
virtual const std::vector<JointPtr>& GetDependencyOrderedJoints() const ; virtual const std::vector<JointPtr>& GetDependencyOrderedJoints() const ;
skipping to change at line 851 skipping to change at line 899
/// ///
/// Takes into account joint limits and wrapping of circular joints. /// Takes into account joint limits and wrapping of circular joints.
virtual void SubtractDOFValues(std::vector<dReal>& values1, const std:: vector<dReal>& values2) const; virtual void SubtractDOFValues(std::vector<dReal>& values1, const std:: vector<dReal>& values2) const;
/// \deprecated (01/01/11) /// \deprecated (01/01/11)
virtual void SubtractJointValues(std::vector<dReal>& q1, const std::vec tor<dReal>& q2) const RAVE_DEPRECATED { SubtractDOFValues(q1,q2); } virtual void SubtractJointValues(std::vector<dReal>& q1, const std::vec tor<dReal>& q2) const RAVE_DEPRECATED { SubtractDOFValues(q1,q2); }
/// \brief Adds a torque to every joint. /// \brief Adds a torque to every joint.
/// ///
/// \param bAdd if true, adds to previous torques, otherwise resets the torques on all bodies and starts from 0 /// \param bAdd if true, adds to previous torques, otherwise resets the torques on all bodies and starts from 0
virtual void SetJointTorques(const std::vector<dReal>& torques, bool ad virtual void SetDOFTorques(const std::vector<dReal>& torques, bool add)
d); ;
/// \deprecated (11/06/17)
virtual void SetJointTorques(const std::vector<dReal>& torques, bool ad
d) RAVE_DEPRECATED { SetDOFTorques(torques,add); }
/// \brief Returns all the rigid links of the body. /// \brief Returns all the rigid links of the body.
virtual const std::vector<LinkPtr>& GetLinks() const { return _veclinks ; } virtual const std::vector<LinkPtr>& GetLinks() const { return _veclinks ; }
/// return a pointer to the link with the given name /// return a pointer to the link with the given name
virtual LinkPtr GetLink(const std::string& name) const; virtual LinkPtr GetLink(const std::string& name) const;
/// Updates the bounding box and any other parameters that could have c hanged by a simulation step /// Updates the bounding box and any other parameters that could have c hanged by a simulation step
virtual void SimulationStep(dReal fElapsedTime); virtual void SimulationStep(dReal fElapsedTime);
virtual void GetBodyTransformations(std::vector<Transform>& vtrans) con
st; /// \brief get the transformations of all the links at once
virtual void GetLinkTransformations(std::vector<Transform>& transforms)
const;
/// \deprecated (11/05/26)
virtual void GetBodyTransformations(std::vector<Transform>& transforms)
const RAVE_DEPRECATED {
GetLinkTransformations(transforms);
}
/// queries the transfromation of the first link of the body /// queries the transfromation of the first link of the body
virtual Transform GetTransform() const; virtual Transform GetTransform() const;
/// \brief Set the velocity of the base link, rest of links are set to a consistent velocity so entire robot moves correctly. /// \brief Set the velocity of the base link, rest of links are set to a consistent velocity so entire robot moves correctly.
/// \param linearvel linear velocity /// \param linearvel linear velocity
/// \param angularvel is the rotation axis * angular speed /// \param angularvel is the rotation axis * angular speed
virtual bool SetVelocity(const Vector& linearvel, const Vector& angular vel); virtual bool SetVelocity(const Vector& linearvel, const Vector& angular vel);
/** \brief Sets the velocity of the base link and each of the joints. /** \brief Sets the velocity of the base link and each of the joints.
Computes internally what the correponding velocities of each of the links should be in order to Computes internally what the correponding velocities of each of the links should be in order to
achieve consistent results with the joint velocities. Sends the vel ocities to the physics engine. achieve consistent results with the joint velocities. Sends the vel ocities to the physics engine.
Velocities correspond to the link's coordinate system origin. Velocities correspond to the link's coordinate system origin.
\param[in] linearvel linear velocity of base link \param[in] linearvel linear velocity of base link
\param[in] angularvel angular velocity rotation_axis*theta_dot \param[in] angularvel angular velocity rotation_axis*theta_dot
\param[in] vDOFVelocities - velocities of each of the degrees of fr eeom \param[in] vDOFVelocities - velocities of each of the degrees of fr eeom
\param checklimits if true, will excplicitly check the joint veloci ty limits before setting the values. \param checklimits if true, will excplicitly check the joint veloci ty limits before setting the values.
*/ */
virtual bool SetDOFVelocities(const std::vector<dReal>& vDOFVelocities, virtual void SetDOFVelocities(const std::vector<dReal>& vDOFVelocities,
const Vector& linearvel, const Vector& linearvel, const Vector& angularvel,bool checklimits = false
const Vector& angularvel,bool checklimits );
= false);
/// \brief Sets the velocity of the joints. /// \brief Sets the velocity of the joints.
/// ///
/// Copies the current velocity of the base link and calls SetDOFVeloci ties(linearvel,angularvel,vDOFVelocities) /// Copies the current velocity of the base link and calls SetDOFVeloci ties(linearvel,angularvel,vDOFVelocities)
/// \param[in] vDOFVelocity - velocities of each of the degrees of free om /// \param[in] vDOFVelocity - velocities of each of the degrees of free om
/// \praam checklimits if true, will excplicitly check the joint veloci ty limits before setting the values. /// \praam checklimits if true, will excplicitly check the joint veloci ty limits before setting the values.
virtual bool SetDOFVelocities(const std::vector<dReal>& vDOFVelocities, bool checklimits = false); virtual void SetDOFVelocities(const std::vector<dReal>& vDOFVelocities, bool checklimits = false);
/// \brief Returns the linear and angular velocities for each link /// \brief Returns the linear and angular velocities for each link
virtual bool GetLinkVelocities(std::vector<std::pair<Vector,Vector> >& velocities) const; virtual void GetLinkVelocities(std::vector<std::pair<Vector,Vector> >& velocities) const;
/** \en \brief set the transform of the first link (the rest of the lin ks are computed based on the joint values). /** \en \brief set the transform of the first link (the rest of the lin ks are computed based on the joint values).
\param transform affine transformation \param transform affine transformation
\ja \brief 胴体の絶対姿勢を設定、残りのリンクは運動学の構造に従って変換される. \ja \brief 胴体の絶対姿勢を設定、残りのリンクは運動学の構造に従って変換される.
\param transform 変換行列 \param transform 変換行列
*/ */
virtual void SetTransform(const Transform& transform); virtual void SetTransform(const Transform& transform);
/// \brief Return an axis-aligned bounding box of the entire object. /// \brief Return an axis-aligned bounding box of the entire object in the world coordinate system.
virtual AABB ComputeAABB() const; virtual AABB ComputeAABB() const;
/// \brief Return the center of mass of entire robot. /// \brief Return the center of mass of entire robot in the world coord inate system.
virtual Vector GetCenterOfMass() const; virtual Vector GetCenterOfMass() const;
/// \brief Enables or disables the bodies. /// \brief Enables or disables the bodies.
virtual void Enable(bool enable); virtual void Enable(bool enable);
/// \deprecated (10/09/08) /// \deprecated (10/09/08)
virtual void EnableLink(LinkPtr plink, bool bEnable) RAVE_DEPRECATED { plink->Enable(bEnable); } virtual void EnableLink(LinkPtr plink, bool bEnable) RAVE_DEPRECATED { plink->Enable(bEnable); }
/// \return true if any link of the KinBody is enabled /// \return true if any link of the KinBody is enabled
virtual bool IsEnabled() const; virtual bool IsEnabled() const;
skipping to change at line 941 skipping to change at line 998
/// \param values the values to set the joint angles (ordered by the do f indices) /// \param values the values to set the joint angles (ordered by the do f indices)
/// \param transform represents the transformation of the first body. /// \param transform represents the transformation of the first body.
/// \praam checklimits if true, will excplicitly check the joint limits before setting the values. /// \praam checklimits if true, will excplicitly check the joint limits before setting the values.
virtual void SetDOFValues(const std::vector<dReal>& values, const Trans form& transform, bool checklimits = false); virtual void SetDOFValues(const std::vector<dReal>& values, const Trans form& transform, bool checklimits = false);
virtual void SetJointValues(const std::vector<dReal>& values, const Tra nsform& transform, bool checklimits = false) virtual void SetJointValues(const std::vector<dReal>& values, const Tra nsform& transform, bool checklimits = false)
{ {
SetDOFValues(values,transform,checklimits); SetDOFValues(values,transform,checklimits);
} }
virtual void SetBodyTransformations(const std::vector<Transform>& trans /// \brief sets the transformations of all the links at once
forms); virtual void SetLinkTransformations(const std::vector<Transform>& trans
forms);
/// \deprecated (11/05/26)
virtual void SetBodyTransformations(const std::vector<Transform>& trans
forms) RAVE_DEPRECATED { SetLinkTransformations(transforms); }
/// \brief sets the link velocities
virtual void SetLinkVelocities(const std::vector<std::pair<Vector,Vecto
r> >& velocities);
/// \brief Computes the translation jacobian with respect to a world po sition. /// \brief Computes the translation jacobian with respect to a world po sition.
/// ///
/// Gets the jacobian with respect to a link by computing the partial d ifferentials for all joints that in the path from the root node to GetLinks ()[index] /// Gets the jacobian with respect to a link by computing the partial d ifferentials for all joints that in the path from the root node to GetLinks ()[index]
/// (doesn't touch the rest of the values) /// (doesn't touch the rest of the values)
/// \param linkindex of the link that the rotation is attached to /// \param linkindex of the link that the rotation is attached to
/// \param position position in world space where to compute derivative s from. /// \param position position in world space where to compute derivative s from.
/// \param vjacobian 3xDOF matrix /// \param vjacobian 3xDOF matrix
virtual void CalculateJacobian(int linkindex, const Vector& offset, boo st::multi_array<dReal,2>& vjacobian) const; virtual void CalculateJacobian(int linkindex, const Vector& offset, boo st::multi_array<dReal,2>& vjacobian) const;
virtual void CalculateJacobian(int linkindex, const Vector& offset, std ::vector<dReal>& pfJacobian) const; virtual void CalculateJacobian(int linkindex, const Vector& offset, std ::vector<dReal>& pfJacobian) const;
skipping to change at line 988 skipping to change at line 1052
/// \brief Return true if this body is derived from RobotBase. /// \brief Return true if this body is derived from RobotBase.
virtual bool IsRobot() const { return false; } virtual bool IsRobot() const { return false; }
/// \brief return a unique id of the body used in the environment. /// \brief return a unique id of the body used in the environment.
/// ///
/// If object is not added to the environment, this will return 0. So c hecking if GetEnvironmentId() is 0 is a good way to check if object is pres ent in the environment. /// If object is not added to the environment, this will return 0. So c hecking if GetEnvironmentId() is 0 is a good way to check if object is pres ent in the environment.
/// This id will not be copied when cloning in order to respect another environment's ids. /// This id will not be copied when cloning in order to respect another environment's ids.
virtual int GetEnvironmentId() const; virtual int GetEnvironmentId() const;
/// \deprecated (10/07/01)
virtual int GetNetworkId() const RAVE_DEPRECATED { return GetEnvironmen
tId(); }
/** \brief Returns a nonzero value if the joint effects the link transf ormation. /** \brief Returns a nonzero value if the joint effects the link transf ormation.
In closed loops, all joints on all paths to the root link are count ed as affecting the link. In closed loops, all joints on all paths to the root link are count ed as affecting the link.
If a mimic joint affects the link, then all the joints used in the mimic joint's computation affect the link. If a mimic joint affects the link, then all the joints used in the mimic joint's computation affect the link.
If negative, the partial derivative of the Jacobian should be negat ed. If negative, the partial derivative of the Jacobian should be negat ed.
\param jointindex index of the joint \param jointindex index of the joint
\param linkindex index of the link \param linkindex index of the link
*/ */
virtual int8_t DoesAffect(int jointindex, int linkindex) const; virtual int8_t DoesAffect(int jointindex, int linkindex) const;
skipping to change at line 1063 skipping to change at line 1124
virtual const std::string& GetKinematicsGeometryHash() const; virtual const std::string& GetKinematicsGeometryHash() const;
/// \deprecated (10/11/18) /// \deprecated (10/11/18)
virtual void SetJointVelocities(const std::vector<dReal>& pJointVelocit ies) RAVE_DEPRECATED { virtual void SetJointVelocities(const std::vector<dReal>& pJointVelocit ies) RAVE_DEPRECATED {
SetDOFVelocities(pJointVelocities); SetDOFVelocities(pJointVelocities);
} }
/// \deprecated (10/11/18) /// \deprecated (10/11/18)
virtual void GetVelocity(Vector& linearvel, Vector& angularvel) const R AVE_DEPRECATED; virtual void GetVelocity(Vector& linearvel, Vector& angularvel) const R AVE_DEPRECATED;
/// \brief Sets the joint offsets so that the current configuration bec
omes the new zero state of the robot.
///
/// When this function returns, the returned DOF values should be all z
ero for controllable joints.
/// Mimic equations will use the new offsetted values when computing th
eir joints.
/// This is primarily used for calibrating a robot's zero position
virtual void SetZeroConfiguration();
protected: protected:
/// \brief constructors declared protected so that user always goes thr ough environment to create bodies /// \brief constructors declared protected so that user always goes thr ough environment to create bodies
KinBody(InterfaceType type, EnvironmentBasePtr penv); KinBody(InterfaceType type, EnvironmentBasePtr penv);
inline KinBodyPtr shared_kinbody() { return boost::static_pointer_cast< KinBody>(shared_from_this()); } inline KinBodyPtr shared_kinbody() { return boost::static_pointer_cast< KinBody>(shared_from_this()); }
inline KinBodyConstPtr shared_kinbody_const() const { return boost::sta tic_pointer_cast<KinBody const>(shared_from_this()); } inline KinBodyConstPtr shared_kinbody_const() const { return boost::sta tic_pointer_cast<KinBody const>(shared_from_this()); }
/// \brief custom data managed by the current active physics engine, sh ould be set only by PhysicsEngineBase /// \brief custom data managed by the current active physics engine, sh ould be set only by PhysicsEngineBase
virtual void SetPhysicsData(UserDataPtr pdata) { _pPhysicsData = pdata; } virtual void SetPhysicsData(UserDataPtr pdata) { _pPhysicsData = pdata; }
/// \brief custom data managed by the current active collision checker, should be set only by CollisionCheckerBase /// \brief custom data managed by the current active collision checker, should be set only by CollisionCheckerBase
virtual void SetCollisionData(UserDataPtr pdata) { _pCollisionData = pd ata; } virtual void SetCollisionData(UserDataPtr pdata) { _pCollisionData = pd ata; }
skipping to change at line 1136 skipping to change at line 1204
mutable int _nNonAdjacentLinkCache; ///< specifies what information is currently valid in the AdjacentOptions. Declared as mutable since data is cached. If 0x80000000 (ie < 0), then everything needs to be recomputed incl uding _setNonAdjacentLinks[0]. mutable int _nNonAdjacentLinkCache; ///< specifies what information is currently valid in the AdjacentOptions. Declared as mutable since data is cached. If 0x80000000 (ie < 0), then everything needs to be recomputed incl uding _setNonAdjacentLinks[0].
std::vector<Transform> _vInitialLinkTransformations; ///< the initial t ransformations of each link specifying at least one pose where the robot is collision free std::vector<Transform> _vInitialLinkTransformations; ///< the initial t ransformations of each link specifying at least one pose where the robot is collision free
int _environmentid; ///< \see GetEnvironmentId int _environmentid; ///< \see GetEnvironmentId
mutable int _nUpdateStampId; ///< \see GetUpdateStamp mutable int _nUpdateStampId; ///< \see GetUpdateStamp
int _nParametersChanged; ///< set of parameters that changed and need c allbacks int _nParametersChanged; ///< set of parameters that changed and need c allbacks
UserDataPtr _pGuiData; ///< \see SetGuiData UserDataPtr _pGuiData; ///< \see SetGuiData
UserDataPtr _pPhysicsData; ///< \see SetPhysicsData UserDataPtr _pPhysicsData; ///< \see SetPhysicsData
UserDataPtr _pCollisionData; ///< \see SetCollisionData UserDataPtr _pCollisionData; ///< \see SetCollisionData
ManageDataPtr _pManageData; ManageDataPtr _pManageData;
uint8_t _nHierarchyComputed; ///< true if the joint heirarchy and other cached information is computed uint32_t _nHierarchyComputed; ///< true if the joint heirarchy and othe r cached information is computed
bool _bMakeJoinedLinksAdjacent; bool _bMakeJoinedLinksAdjacent;
private: private:
std::string __hashkinematics; mutable std::string __hashkinematics;
mutable std::vector<dReal> _vTempJoints; mutable std::vector<dReal> _vTempJoints;
virtual const char* GetHash() const { return OPENRAVE_KINBODY_HASH; } virtual const char* GetHash() const { return OPENRAVE_KINBODY_HASH; }
static void __erase_iterator(KinBodyWeakPtr pweakbody, std::list<std::p air<int,boost::function<void()> > >::iterator* pit); static void __erase_iterator(KinBodyWeakPtr pweakbody, std::list<std::p air<int,boost::function<void()> > >::iterator* pit);
#ifdef RAVE_PRIVATE #ifdef RAVE_PRIVATE
#ifdef _MSC_VER #ifdef _MSC_VER
friend class Environment; friend class Environment;
friend class ColladaReader; friend class ColladaReader;
friend class ColladaWriter; friend class ColladaWriter;
 End of changes. 56 change blocks. 
114 lines changed or deleted 205 lines changed or added


 openrave.h   openrave.h 
skipping to change at line 81 skipping to change at line 81
#include <boost/enable_shared_from_this.hpp> #include <boost/enable_shared_from_this.hpp>
#include <boost/thread/mutex.hpp> #include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp> #include <boost/thread/thread.hpp>
#include <boost/thread/recursive_mutex.hpp> #include <boost/thread/recursive_mutex.hpp>
#include <boost/static_assert.hpp> #include <boost/static_assert.hpp>
#include <boost/format.hpp> #include <boost/format.hpp>
#include <boost/array.hpp> #include <boost/array.hpp>
#include <boost/multi_array.hpp> #include <boost/multi_array.hpp>
//#include <boost/cstdint.hpp> //#include <boost/cstdint.hpp>
#if defined(_WIN32) || defined(__CYGWIN__) || defined(_MSC_VER)
#define OPENRAVE_HELPER_DLL_IMPORT __declspec(dllimport)
#define OPENRAVE_HELPER_DLL_EXPORT __declspec(dllexport)
#define OPENRAVE_HELPER_DLL_LOCAL
#else
#if __GNUC__ >= 4
#define OPENRAVE_HELPER_DLL_IMPORT __attribute__ ((visibility("default"
)))
#define OPENRAVE_HELPER_DLL_EXPORT __attribute__ ((visibility("default"
)))
#define OPENRAVE_HELPER_DLL_LOCAL __attribute__ ((visibility("hidden")
))
#else
#define OPENRAVE_HELPER_DLL_IMPORT
#define OPENRAVE_HELPER_DLL_EXPORT
#define OPENRAVE_HELPER_DLL_LOCAL
#endif
#endif
// Now we use the generic helper definitions above to define OPENRAVE_API a
nd OPENRAVE_LOCAL.
// OPENRAVE_API is used for the public API symbols. It either DLL imports o
r DLL exports (or does nothing for static build)
// OPENRAVE_LOCAL is used for non-api symbols.
#if defined(OPENRAVE_DLL) || defined(OPENRAVE_CORE_DLL) // defined if OpenR
AVE is compiled as a DLL
#ifdef OPENRAVE_DLL_EXPORTS // defined if we are building the OpenRAVE DL
L (instead of using it)
#define OPENRAVE_API OPENRAVE_HELPER_DLL_EXPORT
#else
#define OPENRAVE_API OPENRAVE_HELPER_DLL_IMPORT
#endif // OPENRAVE_DLL_EXPORTS
#define OPENRAVE_LOCAL OPENRAVE_HELPER_DLL_LOCAL
#else // OPENRAVE_DLL is not defined: this means OpenRAVE is a static lib.
#define OPENRAVE_API
#define OPENRAVE_LOCAL
#endif // OPENRAVE_DLL
#if defined(__GNUC__) #if defined(__GNUC__)
#define RAVE_DEPRECATED __attribute__((deprecated)) #define RAVE_DEPRECATED __attribute__((deprecated))
#else #else
#define RAVE_DEPRECATED #define RAVE_DEPRECATED
#endif #endif
/// The entire %OpenRAVE library /// The entire %OpenRAVE library
namespace OpenRAVE { namespace OpenRAVE {
#include <openrave/config.h> #include <openrave/config.h>
skipping to change at line 178 skipping to change at line 147
/// %OpenRAVE error codes /// %OpenRAVE error codes
enum OpenRAVEErrorCode { enum OpenRAVEErrorCode {
ORE_Failed=0, ORE_Failed=0,
ORE_InvalidArguments=1, ORE_InvalidArguments=1,
ORE_EnvironmentNotLocked=2, ORE_EnvironmentNotLocked=2,
ORE_CommandNotSupported=3, ///< string command could not be parsed or i s not supported ORE_CommandNotSupported=3, ///< string command could not be parsed or i s not supported
ORE_Assert=4, ORE_Assert=4,
ORE_InvalidPlugin=5, ///< shared object is not a valid plugin ORE_InvalidPlugin=5, ///< shared object is not a valid plugin
ORE_InvalidInterfaceHash=6, ///< interface hashes do not match between plugins ORE_InvalidInterfaceHash=6, ///< interface hashes do not match between plugins
ORE_NotImplemented=7, ///< function is not implemented by the interface . ORE_NotImplemented=7, ///< function is not implemented by the interface .
ORE_InconsistentConstraints=8, ///< return solutions or trajectories do not follow the constraints of the planner/module
}; };
/// \brief Exception that all OpenRAVE internal methods throw; the error co des are held in \ref OpenRAVEErrorCode. /// \brief Exception that all OpenRAVE internal methods throw; the error co des are held in \ref OpenRAVEErrorCode.
class OPENRAVE_API openrave_exception : public std::exception class OPENRAVE_API openrave_exception : public std::exception
{ {
public: public:
openrave_exception() : std::exception(), _s("unknown exception"), _erro r(ORE_Failed) {} openrave_exception() : std::exception(), _s("unknown exception"), _erro r(ORE_Failed) {}
openrave_exception(const std::string& s, OpenRAVEErrorCode error=ORE_Fa iled) : std::exception() { openrave_exception(const std::string& s, OpenRAVEErrorCode error=ORE_Fa iled) : std::exception() {
_error = error; _error = error;
_s = "openrave ("; _s = "openrave (";
skipping to change at line 331 skipping to change at line 301
str[positions[i]] = 'S'; str[positions[i]] = 'S';
return str; return str;
} }
enum DebugLevel { enum DebugLevel {
Level_Fatal=0, Level_Fatal=0,
Level_Error=1, Level_Error=1,
Level_Warn=2, Level_Warn=2,
Level_Info=3, Level_Info=3,
Level_Debug=4, Level_Debug=4,
Level_Verbose=5 Level_Verbose=5,
Level_OutputMask=0xf,
Level_VerifyPlans=0x80000000, ///< if set, should verify every plan ret
urned. the verification is left up to the planners or the modules calling t
he planners. See \ref planningutils::ValidateTrajectory
}; };
#define OPENRAVECOLOR_FATALLEVEL 5 // magenta #define OPENRAVECOLOR_FATALLEVEL 5 // magenta
#define OPENRAVECOLOR_ERRORLEVEL 1 // red #define OPENRAVECOLOR_ERRORLEVEL 1 // red
#define OPENRAVECOLOR_WARNLEVEL 3 // yellow #define OPENRAVECOLOR_WARNLEVEL 3 // yellow
#define OPENRAVECOLOR_INFOLEVEL 0 // black #define OPENRAVECOLOR_INFOLEVEL 0 // black
#define OPENRAVECOLOR_DEBUGLEVEL 2 // green #define OPENRAVECOLOR_DEBUGLEVEL 2 // green
#define OPENRAVECOLOR_VERBOSELEVEL 4 // blue #define OPENRAVECOLOR_VERBOSELEVEL 4 // blue
/// Random number generation /// \brief Sets the global openrave debug level. A combination of \ref Debu
//@{ gLevel
enum IntervalType { OPENRAVE_API void RaveSetDebugLevel(uint32_t level);
IT_Open=0, ///< (a,b)
IT_OpenStart=1, ///< (a,b]
IT_OpenEnd=2, ///< [a,b)
IT_Closed=3, ///< [a,b]
};
OPENRAVE_API void RaveInitRandomGeneration(uint32_t seed);
/// generate a random integer, 32bit precision
OPENRAVE_API uint32_t RaveRandomInt();
/// generate n random integers, 32bit precision
OPENRAVE_API void RaveRandomInt(int n, std::vector<int>& v);
/// \brief generate a random float in 0-1
///
/// \param interval specifies inclusion of 0 and 1 in the result
OPENRAVE_API float RaveRandomFloat(IntervalType interval=IT_Closed);
/// \deprecated (10/11/27)
OPENRAVE_API void RaveRandomFloat(int n, std::vector<float>& v) RAVE_DEPREC
ATED;
/// \brief generate a random double in 0-1, 53bit precision
///
/// \param interval specifies inclusion of 0 and 1 in the result
OPENRAVE_API double RaveRandomDouble(IntervalType interval=IT_Closed);
/// \deprecated (10/11/27)
OPENRAVE_API void RaveRandomDouble(int n, std::vector<double>& v) RAVE_DEPR
ECATED;
//@}
/// Sets the global openrave debug level
OPENRAVE_API void RaveSetDebugLevel(DebugLevel level);
/// Returns the openrave debug level /// Returns the openrave debug level
OPENRAVE_API DebugLevel RaveGetDebugLevel(); OPENRAVE_API int RaveGetDebugLevel();
/// extracts only the filename /// extracts only the filename
inline const char* RaveGetSourceFilename(const char* pfilename) inline const char* RaveGetSourceFilename(const char* pfilename)
{ {
if( pfilename == NULL ) { if( pfilename == NULL ) {
return ""; return "";
} }
const char* p0 = strrchr(pfilename,'/'); const char* p0 = strrchr(pfilename,'/');
const char* p1 = strrchr(pfilename,'\\'); const char* p1 = strrchr(pfilename,'\\');
const char* p = p0 > p1 ? p0 : p1; const char* p = p0 > p1 ? p0 : p1;
skipping to change at line 432 skipping to change at line 372
/*ChangeTextColor (stdout, 0, OPENRAVECOLOR##LEVEL);*/ \ /*ChangeTextColor (stdout, 0, OPENRAVECOLOR##LEVEL);*/ \
va_list list; \ va_list list; \
va_start(list,fmt); \ va_start(list,fmt); \
int r = vprintf(fmt, list); \ int r = vprintf(fmt, list); \
va_end(list); \ va_end(list); \
/*if( fmt[0] != '\n' ) { printf("\n"); }*/ \ /*if( fmt[0] != '\n' ) { printf("\n"); }*/ \
/*ResetTextColor(stdout);*/ \ /*ResetTextColor(stdout);*/ \
return r; \ return r; \
} }
inline int RavePrintfA(const std::string& s, DebugLevel level) inline int RavePrintfA(const std::string& s, uint32_t level)
{ {
if( s.size() == 0 || s[s.size()-1] != '\n' ) { // automatically add a n ew line if( s.size() == 0 || s[s.size()-1] != '\n' ) { // automatically add a n ew line
printf("%s\n", s.c_str()); printf("%s\n", s.c_str());
} }
else { else {
printf ("%s", s.c_str()); printf ("%s", s.c_str());
} }
return s.size(); return s.size();
} }
skipping to change at line 511 skipping to change at line 451
inline int RavePrintfA##LEVEL(const char *fmt, ...) \ inline int RavePrintfA##LEVEL(const char *fmt, ...) \
{ \ { \
va_list list; \ va_list list; \
va_start(list,fmt); \ va_start(list,fmt); \
int r = vprintf((ChangeTextColor(0, OPENRAVECOLOR##LEVEL,8) + std:: string(fmt) + ResetTextColor()).c_str(), list); \ int r = vprintf((ChangeTextColor(0, OPENRAVECOLOR##LEVEL,8) + std:: string(fmt) + ResetTextColor()).c_str(), list); \
va_end(list); \ va_end(list); \
/*if( fmt[0] != '\n' ) { printf("\n"); } */ \ /*if( fmt[0] != '\n' ) { printf("\n"); } */ \
return r; \ return r; \
} \ } \
inline int RavePrintfA(const std::string& s, DebugLevel level) inline int RavePrintfA(const std::string& s, uint32_t level)
{ {
if( OpenRAVE::RaveGetDebugLevel()>=level ) { if( (OpenRAVE::RaveGetDebugLevel()&OpenRAVE::Level_OutputMask)>=level ) {
int color = 0; int color = 0;
switch(level) { switch(level) {
case Level_Fatal: color = OPENRAVECOLOR_FATALLEVEL; break; case Level_Fatal: color = OPENRAVECOLOR_FATALLEVEL; break;
case Level_Error: color = OPENRAVECOLOR_ERRORLEVEL; break; case Level_Error: color = OPENRAVECOLOR_ERRORLEVEL; break;
case Level_Warn: color = OPENRAVECOLOR_WARNLEVEL; break; case Level_Warn: color = OPENRAVECOLOR_WARNLEVEL; break;
case Level_Info: // print regular case Level_Info: // print regular
if( s.size() == 0 || s[s.size()-1] != '\n' ) { // automatically add a new line if( s.size() == 0 || s[s.size()-1] != '\n' ) { // automatically add a new line
printf ("%s\n",s.c_str()); printf ("%s\n",s.c_str());
} }
else { else {
skipping to change at line 561 skipping to change at line 501
DefineRavePrintfA(_ERRORLEVEL) DefineRavePrintfA(_ERRORLEVEL)
DefineRavePrintfA(_WARNLEVEL) DefineRavePrintfA(_WARNLEVEL)
//DefineRavePrintfA(_INFOLEVEL) //DefineRavePrintfA(_INFOLEVEL)
DefineRavePrintfA(_DEBUGLEVEL) DefineRavePrintfA(_DEBUGLEVEL)
DefineRavePrintfA(_VERBOSELEVEL) DefineRavePrintfA(_VERBOSELEVEL)
#define RAVEPRINTHEADER(LEVEL) OpenRAVE::RavePrintfA##LEVEL("[%s:%d] ", Ope nRAVE::RaveGetSourceFilename(__FILE__), __LINE__) #define RAVEPRINTHEADER(LEVEL) OpenRAVE::RavePrintfA##LEVEL("[%s:%d] ", Ope nRAVE::RaveGetSourceFilename(__FILE__), __LINE__)
// different logging levels. The higher the suffix number, the less importa nt the information is. // different logging levels. The higher the suffix number, the less importa nt the information is.
// 0 log level logs all the time. OpenRAVE starts up with a log level of 0. // 0 log level logs all the time. OpenRAVE starts up with a log level of 0.
#define RAVELOG_LEVELW(LEVEL,level) OpenRAVE::RaveGetDebugLevel()>=(level)& #define RAVELOG_LEVELW(LEVEL,level) (OpenRAVE::RaveGetDebugLevel()&OpenRAVE
&(RAVEPRINTHEADER(LEVEL)>0)&&OpenRAVE::RavePrintfW##LEVEL ::Level_OutputMask)>=(level)&&(RAVEPRINTHEADER(LEVEL)>0)&&OpenRAVE::RavePri
#define RAVELOG_LEVELA(LEVEL,level) OpenRAVE::RaveGetDebugLevel()>=(level)& ntfW##LEVEL
&(RAVEPRINTHEADER(LEVEL)>0)&&OpenRAVE::RavePrintfA##LEVEL #define RAVELOG_LEVELA(LEVEL,level) (OpenRAVE::RaveGetDebugLevel()&OpenRAVE
::Level_OutputMask)>=(level)&&(RAVEPRINTHEADER(LEVEL)>0)&&OpenRAVE::RavePri
ntfA##LEVEL
// define log4cxx equivalents (eventually OpenRAVE will move to log4cxx log ging) // define log4cxx equivalents (eventually OpenRAVE will move to log4cxx log ging)
#define RAVELOG_FATALW RAVELOG_LEVELW(_FATALLEVEL,OpenRAVE::Level_Fatal) #define RAVELOG_FATALW RAVELOG_LEVELW(_FATALLEVEL,OpenRAVE::Level_Fatal)
#define RAVELOG_FATALA RAVELOG_LEVELA(_FATALLEVEL,OpenRAVE::Level_Fatal) #define RAVELOG_FATALA RAVELOG_LEVELA(_FATALLEVEL,OpenRAVE::Level_Fatal)
#define RAVELOG_FATAL RAVELOG_FATALA #define RAVELOG_FATAL RAVELOG_FATALA
#define RAVELOG_ERRORW RAVELOG_LEVELW(_ERRORLEVEL,OpenRAVE::Level_Error) #define RAVELOG_ERRORW RAVELOG_LEVELW(_ERRORLEVEL,OpenRAVE::Level_Error)
#define RAVELOG_ERRORA RAVELOG_LEVELA(_ERRORLEVEL,OpenRAVE::Level_Error) #define RAVELOG_ERRORA RAVELOG_LEVELA(_ERRORLEVEL,OpenRAVE::Level_Error)
#define RAVELOG_ERROR RAVELOG_ERRORA #define RAVELOG_ERROR RAVELOG_ERRORA
#define RAVELOG_WARNW RAVELOG_LEVELW(_WARNLEVEL,OpenRAVE::Level_Warn) #define RAVELOG_WARNW RAVELOG_LEVELW(_WARNLEVEL,OpenRAVE::Level_Warn)
#define RAVELOG_WARNA RAVELOG_LEVELA(_WARNLEVEL,OpenRAVE::Level_Warn) #define RAVELOG_WARNA RAVELOG_LEVELA(_WARNLEVEL,OpenRAVE::Level_Warn)
skipping to change at line 584 skipping to change at line 524
#define RAVELOG_INFOW RAVELOG_LEVELW(_INFOLEVEL,OpenRAVE::Level_Info) #define RAVELOG_INFOW RAVELOG_LEVELW(_INFOLEVEL,OpenRAVE::Level_Info)
#define RAVELOG_INFOA RAVELOG_LEVELA(_INFOLEVEL,OpenRAVE::Level_Info) #define RAVELOG_INFOA RAVELOG_LEVELA(_INFOLEVEL,OpenRAVE::Level_Info)
#define RAVELOG_INFO RAVELOG_INFOA #define RAVELOG_INFO RAVELOG_INFOA
#define RAVELOG_DEBUGW RAVELOG_LEVELW(_DEBUGLEVEL,OpenRAVE::Level_Debug) #define RAVELOG_DEBUGW RAVELOG_LEVELW(_DEBUGLEVEL,OpenRAVE::Level_Debug)
#define RAVELOG_DEBUGA RAVELOG_LEVELA(_DEBUGLEVEL,OpenRAVE::Level_Debug) #define RAVELOG_DEBUGA RAVELOG_LEVELA(_DEBUGLEVEL,OpenRAVE::Level_Debug)
#define RAVELOG_DEBUG RAVELOG_DEBUGA #define RAVELOG_DEBUG RAVELOG_DEBUGA
#define RAVELOG_VERBOSEW RAVELOG_LEVELW(_VERBOSELEVEL,OpenRAVE::Level_Verbo se) #define RAVELOG_VERBOSEW RAVELOG_LEVELW(_VERBOSELEVEL,OpenRAVE::Level_Verbo se)
#define RAVELOG_VERBOSEA RAVELOG_LEVELA(_VERBOSELEVEL,OpenRAVE::Level_Verbo se) #define RAVELOG_VERBOSEA RAVELOG_LEVELA(_VERBOSELEVEL,OpenRAVE::Level_Verbo se)
#define RAVELOG_VERBOSE RAVELOG_VERBOSEA #define RAVELOG_VERBOSE RAVELOG_VERBOSEA
#define IS_DEBUGLEVEL(level) (OpenRAVE::RaveGetDebugLevel()>=(level)) #define IS_DEBUGLEVEL(level) ((OpenRAVE::RaveGetDebugLevel()&OpenRAVE::Leve
l_OutputMask)>=(level))
#define OPENRAVE_EXCEPTION_FORMAT0(s, errorcode) OpenRAVE::openrave_excepti
on(boost::str(boost::format("[%s:%d] "s)%(__PRETTY_FUNCTION__)%(__LINE__)),
errorcode)
/// adds the function name and line number to an openrave exception
#define OPENRAVE_EXCEPTION_FORMAT(s, args,errorcode) OpenRAVE::openrave_exc
eption(boost::str(boost::format("[%s:%d] "s)%(__PRETTY_FUNCTION__)%(__LINE_
_)%args),errorcode)
#define OPENRAVE_DUMMY_IMPLEMENTATION { throw OPENRAVE_EXCEPTION_FORMAT0("n
ot implemented",ORE_NotImplemented); }
/// \brief Enumeration of all the interfaces. /// \brief Enumeration of all the interfaces.
enum InterfaceType enum InterfaceType
{ {
PT_Planner=1, ///< describes \ref PlannerBase interface PT_Planner=1, ///< describes \ref PlannerBase interface
PT_Robot=2, ///< describes \ref RobotBase interface PT_Robot=2, ///< describes \ref RobotBase interface
PT_SensorSystem=3, ///< describes \ref SensorSystemBase interface PT_SensorSystem=3, ///< describes \ref SensorSystemBase interface
PT_Controller=4, ///< describes \ref ControllerBase interface PT_Controller=4, ///< describes \ref ControllerBase interface
PT_ProblemInstance=5, ///< describes \ref ProblemInstance interface PT_Module=5, ///< describes \ref ModuleBase interface
PT_ProblemInstance=5, ///< describes \ref ModuleBase interface
PT_IkSolver=6, ///< describes \ref IkSolverBase interface PT_IkSolver=6, ///< describes \ref IkSolverBase interface
PT_InverseKinematicsSolver=6, ///< describes \ref IkSolverBase interfac e PT_InverseKinematicsSolver=6, ///< describes \ref IkSolverBase interfac e
PT_KinBody=7, ///< describes \ref KinBody PT_KinBody=7, ///< describes \ref KinBody
PT_PhysicsEngine=8, ///< describes \ref PhysicsEngineBase PT_PhysicsEngine=8, ///< describes \ref PhysicsEngineBase
PT_Sensor=9, ///< describes \ref SensorBase PT_Sensor=9, ///< describes \ref SensorBase
PT_CollisionChecker=10, ///< describes \ref CollisionCheckerBase PT_CollisionChecker=10, ///< describes \ref CollisionCheckerBase
PT_Trajectory=11, ///< describes \ref TrajectoryBase PT_Trajectory=11, ///< describes \ref TrajectoryBase
PT_Viewer=12,///< describes \ref ViewerBase PT_Viewer=12,///< describes \ref ViewerBase
PT_NumberOfInterfaces=12 ///< number of interfaces, do not forget to up PT_SpaceSampler=13, ///< describes \ref SamplerBase
date PT_NumberOfInterfaces=13 ///< number of interfaces, do not forget to up
date
}; };
/// \deprecated (10/01/01)
typedef InterfaceType PluginType RAVE_DEPRECATED;
class CollisionReport; class CollisionReport;
class InterfaceBase; class InterfaceBase;
class IkSolverBase; class IkSolverBase;
class TrajectoryBase; class TrajectoryBase;
class ControllerBase; class ControllerBase;
class PlannerBase; class PlannerBase;
class RobotBase; class RobotBase;
class ProblemInstance; class ModuleBase;
class EnvironmentBase; class EnvironmentBase;
class KinBody; class KinBody;
class SensorSystemBase; class SensorSystemBase;
class PhysicsEngineBase; class PhysicsEngineBase;
class SensorBase; class SensorBase;
class CollisionCheckerBase; class CollisionCheckerBase;
class ViewerBase; class ViewerBase;
class SpaceSamplerBase;
class IkParameterization; class IkParameterization;
typedef boost::shared_ptr<CollisionReport> CollisionReportPtr; typedef boost::shared_ptr<CollisionReport> CollisionReportPtr;
typedef boost::shared_ptr<CollisionReport const> CollisionReportConstPtr; typedef boost::shared_ptr<CollisionReport const> CollisionReportConstPtr;
typedef boost::shared_ptr<InterfaceBase> InterfaceBasePtr; typedef boost::shared_ptr<InterfaceBase> InterfaceBasePtr;
typedef boost::shared_ptr<InterfaceBase const> InterfaceBaseConstPtr; typedef boost::shared_ptr<InterfaceBase const> InterfaceBaseConstPtr;
typedef boost::weak_ptr<InterfaceBase> InterfaceBaseWeakPtr; typedef boost::weak_ptr<InterfaceBase> InterfaceBaseWeakPtr;
typedef boost::shared_ptr<KinBody> KinBodyPtr; typedef boost::shared_ptr<KinBody> KinBodyPtr;
typedef boost::shared_ptr<KinBody const> KinBodyConstPtr; typedef boost::shared_ptr<KinBody const> KinBodyConstPtr;
typedef boost::weak_ptr<KinBody> KinBodyWeakPtr; typedef boost::weak_ptr<KinBody> KinBodyWeakPtr;
skipping to change at line 651 skipping to change at line 598
typedef boost::weak_ptr<ControllerBase> ControllerBaseWeakPtr; typedef boost::weak_ptr<ControllerBase> ControllerBaseWeakPtr;
typedef boost::shared_ptr<IkSolverBase> IkSolverBasePtr; typedef boost::shared_ptr<IkSolverBase> IkSolverBasePtr;
typedef boost::shared_ptr<IkSolverBase const> IkSolverBaseConstPtr; typedef boost::shared_ptr<IkSolverBase const> IkSolverBaseConstPtr;
typedef boost::weak_ptr<IkSolverBase> IkSolverBaseWeakPtr; typedef boost::weak_ptr<IkSolverBase> IkSolverBaseWeakPtr;
typedef boost::shared_ptr<PhysicsEngineBase> PhysicsEngineBasePtr; typedef boost::shared_ptr<PhysicsEngineBase> PhysicsEngineBasePtr;
typedef boost::shared_ptr<PhysicsEngineBase const> PhysicsEngineBaseConstPt r; typedef boost::shared_ptr<PhysicsEngineBase const> PhysicsEngineBaseConstPt r;
typedef boost::weak_ptr<PhysicsEngineBase> PhysicsEngineBaseWeakPtr; typedef boost::weak_ptr<PhysicsEngineBase> PhysicsEngineBaseWeakPtr;
typedef boost::shared_ptr<PlannerBase> PlannerBasePtr; typedef boost::shared_ptr<PlannerBase> PlannerBasePtr;
typedef boost::shared_ptr<PlannerBase const> PlannerBaseConstPtr; typedef boost::shared_ptr<PlannerBase const> PlannerBaseConstPtr;
typedef boost::weak_ptr<PlannerBase> PlannerBaseWeakPtr; typedef boost::weak_ptr<PlannerBase> PlannerBaseWeakPtr;
typedef boost::shared_ptr<ProblemInstance> ProblemInstancePtr; typedef boost::shared_ptr<ModuleBase> ModuleBasePtr;
typedef boost::shared_ptr<ProblemInstance const> ProblemInstanceConstPtr; typedef boost::shared_ptr<ModuleBase const> ModuleBaseConstPtr;
typedef boost::weak_ptr<ProblemInstance> ProblemInstanceWeakPtr; typedef boost::weak_ptr<ModuleBase> ModuleBaseWeakPtr;
typedef boost::shared_ptr<SensorBase> SensorBasePtr; typedef boost::shared_ptr<SensorBase> SensorBasePtr;
typedef boost::shared_ptr<SensorBase const> SensorBaseConstPtr; typedef boost::shared_ptr<SensorBase const> SensorBaseConstPtr;
typedef boost::weak_ptr<SensorBase> SensorBaseWeakPtr; typedef boost::weak_ptr<SensorBase> SensorBaseWeakPtr;
typedef boost::shared_ptr<SensorSystemBase> SensorSystemBasePtr; typedef boost::shared_ptr<SensorSystemBase> SensorSystemBasePtr;
typedef boost::shared_ptr<SensorSystemBase const> SensorSystemBaseConstPtr; typedef boost::shared_ptr<SensorSystemBase const> SensorSystemBaseConstPtr;
typedef boost::weak_ptr<SensorSystemBase> SensorSystemBaseWeakPtr; typedef boost::weak_ptr<SensorSystemBase> SensorSystemBaseWeakPtr;
typedef boost::shared_ptr<TrajectoryBase> TrajectoryBasePtr; typedef boost::shared_ptr<TrajectoryBase> TrajectoryBasePtr;
typedef boost::shared_ptr<TrajectoryBase const> TrajectoryBaseConstPtr; typedef boost::shared_ptr<TrajectoryBase const> TrajectoryBaseConstPtr;
typedef boost::weak_ptr<TrajectoryBase> TrajectoryBaseWeakPtr; typedef boost::weak_ptr<TrajectoryBase> TrajectoryBaseWeakPtr;
typedef boost::shared_ptr<ViewerBase> ViewerBasePtr; typedef boost::shared_ptr<ViewerBase> ViewerBasePtr;
typedef boost::shared_ptr<ViewerBase const> ViewerBaseConstPtr; typedef boost::shared_ptr<ViewerBase const> ViewerBaseConstPtr;
typedef boost::weak_ptr<ViewerBase> ViewerBaseWeakPtr; typedef boost::weak_ptr<ViewerBase> ViewerBaseWeakPtr;
typedef boost::shared_ptr<SpaceSamplerBase> SpaceSamplerBasePtr;
typedef boost::shared_ptr<SpaceSamplerBase const> SpaceSamplerBaseConstPtr;
typedef boost::weak_ptr<SpaceSamplerBase> SpaceSamplerBaseWeakPtr;
typedef boost::shared_ptr<EnvironmentBase> EnvironmentBasePtr; typedef boost::shared_ptr<EnvironmentBase> EnvironmentBasePtr;
typedef boost::shared_ptr<EnvironmentBase const> EnvironmentBaseConstPtr; typedef boost::shared_ptr<EnvironmentBase const> EnvironmentBaseConstPtr;
typedef boost::weak_ptr<EnvironmentBase> EnvironmentBaseWeakPtr; typedef boost::weak_ptr<EnvironmentBase> EnvironmentBaseWeakPtr;
///< Cloning Options for interfaces and environments ///< Cloning Options for interfaces and environments
enum CloningOptions { enum CloningOptions {
Clone_Bodies = 1, ///< clone all the bodies/robots of the environment, exclude attached interfaces like sensors/controllers Clone_Bodies = 1, ///< clone all the bodies/robots of the environment, exclude attached interfaces like sensors/controllers
Clone_Viewer = 2, ///< clone the viewer type, although figures won't be copied, new viewer does try to match views Clone_Viewer = 2, ///< clone the viewer type, although figures won't be copied, new viewer does try to match views
Clone_Simulation = 4, ///< clone the physics engine and simulation stat e (ie, timesteps, gravity) Clone_Simulation = 4, ///< clone the physics engine and simulation stat e (ie, timesteps, gravity)
Clone_RealControllers = 8, ///< if specified, will clone the real contr ollers of all the robots, otherwise each robot gets ideal controller Clone_RealControllers = 8, ///< if specified, will clone the real contr ollers of all the robots, otherwise each robot gets ideal controller
skipping to change at line 908 skipping to change at line 859
inline void SetTranslationDirection(const RAY& ray) RAVE_DEPRECATED { S etTranslationDirection5D(ray); } inline void SetTranslationDirection(const RAY& ray) RAVE_DEPRECATED { S etTranslationDirection5D(ray); }
inline const Transform& GetTransform() const RAVE_DEPRECATED { return _ transform; } inline const Transform& GetTransform() const RAVE_DEPRECATED { return _ transform; }
inline const Vector& GetRotation() const RAVE_DEPRECATED { return _tran sform.rot; } inline const Vector& GetRotation() const RAVE_DEPRECATED { return _tran sform.rot; }
inline const Vector& GetTranslation() const RAVE_DEPRECATED { return _t ransform.trans; } inline const Vector& GetTranslation() const RAVE_DEPRECATED { return _t ransform.trans; }
inline const Vector& GetDirection() const RAVE_DEPRECATED { return _tra nsform.rot; } inline const Vector& GetDirection() const RAVE_DEPRECATED { return _tra nsform.rot; }
inline const Vector& GetLookat() const RAVE_DEPRECATED { return _transf orm.trans; } inline const Vector& GetLookat() const RAVE_DEPRECATED { return _transf orm.trans; }
inline const RAY GetRay() const RAVE_DEPRECATED { return RAY(_transform .trans,_transform.rot); } inline const RAY GetRay() const RAVE_DEPRECATED { return RAY(_transform .trans,_transform.rot); }
inline const RAY GetTranslationDirection() const RAVE_DEPRECATED { retu rn RAY(_transform.trans,_transform.rot); } inline const RAY GetTranslationDirection() const RAVE_DEPRECATED { retu rn RAY(_transform.trans,_transform.rot); }
//@} //@}
/// \brief Computes the distance squared between two IK parmaeterizatio
ns.
inline dReal ComputeDistanceSqr(const IkParameterization& ikparam) cons
t
{
const dReal anglemult = 0.4; // this is a hack that should be remov
ed....
BOOST_ASSERT(_type==ikparam.GetType());
switch(_type) {
case IkParameterization::Type_Transform6D: {
Transform t0 = GetTransform6D(), t1 = ikparam.GetTransform6D();
dReal fcos = RaveFabs(t0.rot.dot(t1.rot));
dReal facos = fcos >= 1 ? 0 : RaveAcos(fcos);
return (t0.trans-t1.trans).lengthsqr3() + anglemult*facos*facos
;
}
case IkParameterization::Type_Rotation3D: {
dReal fcos = RaveFabs(GetRotation3D().dot(ikparam.GetRotation3D
()));
dReal facos = fcos >= 1 ? 0 : RaveAcos(fcos);
return facos*facos;
}
case IkParameterization::Type_Translation3D:
return (GetTranslation3D()-ikparam.GetTranslation3D()).lengthsq
r3();
case IkParameterization::Type_Direction3D: {
dReal fcos = GetDirection3D().dot(ikparam.GetDirection3D());
dReal facos = fcos >= 1 ? 0 : RaveAcos(fcos);
return facos*facos;
}
case IkParameterization::Type_Ray4D: {
Vector pos0 = GetRay4D().pos - GetRay4D().dir*GetRay4D().dir.do
t(GetRay4D().pos);
Vector pos1 = ikparam.GetRay4D().pos - ikparam.GetRay4D().dir*i
kparam.GetRay4D().dir.dot(ikparam.GetRay4D().pos);
dReal fcos = GetRay4D().dir.dot(ikparam.GetRay4D().dir);
dReal facos = fcos >= 1 ? 0 : RaveAcos(fcos);
return (pos0-pos1).lengthsqr3() + anglemult*facos*facos;
}
case IkParameterization::Type_Lookat3D: {
Vector v = GetLookat3D()-ikparam.GetLookat3D();
dReal s = v.dot3(ikparam.GetLookat3DDirection());
if( s >= -1 ) { // ikparam's lookat is always 1 beyond the orig
in, this is just the convention for testing...
v -= s*ikparam.GetLookat3DDirection();
}
return v.lengthsqr3();
}
case IkParameterization::Type_TranslationDirection5D: {
dReal fcos = GetTranslationDirection5D().dir.dot(ikparam.GetTra
nslationDirection5D().dir);
dReal facos = fcos >= 1 ? 0 : RaveAcos(fcos);
return (GetTranslationDirection5D().pos-ikparam.GetTranslationD
irection5D().pos).lengthsqr3() + anglemult*facos*facos;
}
case IkParameterization::Type_TranslationXY2D: {
return (GetTranslationXY2D()-ikparam.GetTranslationXY2D()).leng
thsqr2();
}
case IkParameterization::Type_TranslationXYOrientation3D: {
Vector v0 = GetTranslationXYOrientation3D();
Vector v1 = ikparam.GetTranslationXYOrientation3D();
dReal anglediff = v0.z-v1.z;
if (anglediff < dReal(-PI)) {
anglediff += dReal(2*PI);
while (anglediff < dReal(-PI))
anglediff += dReal(2*PI);
}
else if (anglediff > dReal(PI)) {
anglediff -= dReal(2*PI);
while (anglediff > dReal(PI))
anglediff -= dReal(2*PI);
}
return (v0-v1).lengthsqr2() + anglemult*anglediff*anglediff;
}
case IkParameterization::Type_TranslationLocalGlobal6D: {
std::pair<Vector,Vector> p0 = GetTranslationLocalGlobal6D(), p1
= ikparam.GetTranslationLocalGlobal6D();
return (p0.first-p1.first).lengthsqr3() + (p0.second-p1.second)
.lengthsqr3();
}
default:
BOOST_ASSERT(0);
}
return 1e30;
}
protected: protected:
Transform _transform; Transform _transform;
Type _type; Type _type;
friend IkParameterization operator* (const Transform& t, const IkParame terization& ikparam); friend IkParameterization operator* (const Transform& t, const IkParame terization& ikparam);
friend std::ostream& operator<<(std::ostream& O, const IkParameterizati on& ikparam); friend std::ostream& operator<<(std::ostream& O, const IkParameterizati on& ikparam);
friend std::istream& operator>>(std::istream& I, IkParameterization& ik param); friend std::istream& operator>>(std::istream& I, IkParameterization& ik param);
}; };
inline IkParameterization operator* (const Transform& t, const IkParameteri zation& ikparam) inline IkParameterization operator* (const Transform& t, const IkParameteri zation& ikparam)
skipping to change at line 1029 skipping to change at line 1053
ikparam._type = static_cast<IkParameterization::Type>(type); ikparam._type = static_cast<IkParameterization::Type>(type);
switch(ikparam._type) { switch(ikparam._type) {
case IkParameterization::Type_Transform6D: { Transform t; I >> t; ikpar am.SetTransform6D(t); break; } case IkParameterization::Type_Transform6D: { Transform t; I >> t; ikpar am.SetTransform6D(t); break; }
case IkParameterization::Type_Rotation3D: { Vector v; I >> v; ikparam.S etRotation3D(v); break; } case IkParameterization::Type_Rotation3D: { Vector v; I >> v; ikparam.S etRotation3D(v); break; }
case IkParameterization::Type_Translation3D: { Vector v; I >> v.x >> v. y >> v.z; ikparam.SetTranslation3D(v); break; } case IkParameterization::Type_Translation3D: { Vector v; I >> v.x >> v. y >> v.z; ikparam.SetTranslation3D(v); break; }
case IkParameterization::Type_Direction3D: { Vector v; I >> v.x >> v.y >> v.z; ikparam.SetDirection3D(v); break; } case IkParameterization::Type_Direction3D: { Vector v; I >> v.x >> v.y >> v.z; ikparam.SetDirection3D(v); break; }
case IkParameterization::Type_Ray4D: { RAY r; I >> r; ikparam.SetRay4D( r); break; } case IkParameterization::Type_Ray4D: { RAY r; I >> r; ikparam.SetRay4D( r); break; }
case IkParameterization::Type_Lookat3D: { Vector v; I >> v.x >> v.y >> v.z; ikparam.SetLookat3D(v); break; } case IkParameterization::Type_Lookat3D: { Vector v; I >> v.x >> v.y >> v.z; ikparam.SetLookat3D(v); break; }
case IkParameterization::Type_TranslationDirection5D: { RAY r; I >> r; ikparam.SetTranslationDirection5D(r); break; } case IkParameterization::Type_TranslationDirection5D: { RAY r; I >> r; ikparam.SetTranslationDirection5D(r); break; }
case IkParameterization::Type_TranslationXY2D: { Vector v; I >> v.y >> v.y; ikparam.SetTranslationXY2D(v); break; } case IkParameterization::Type_TranslationXY2D: { Vector v; I >> v.y >> v.y; ikparam.SetTranslationXY2D(v); break; }
case IkParameterization::Type_TranslationXYOrientation3D: { Vector v; I >> v.y >> v.y >> v.z; ikparam.SetTranslationXYOrientation3D(v); break; } case IkParameterization::Type_TranslationXYOrientation3D: { Vector v; I >> v.y >> v.y >> v.z; ikparam.SetTranslationXYOrientation3D(v); break; }
case IkParameterization::Type_TranslationLocalGlobal6D: { Vector localt rans, trans; I >> localtrans.x >> localtrans.y >> localtrans.z >> trans.x > > trans.y >> trans.z; ikparam.SetTranslationLocalGlobal6D(localtrans,trans) ; break; } case IkParameterization::Type_TranslationLocalGlobal6D: { Vector localt rans, trans; I >> localtrans.x >> localtrans.y >> localtrans.z >> trans.x > > trans.y >> trans.z; ikparam.SetTranslationLocalGlobal6D(localtrans,trans) ; break; }
default: throw openrave_exception(str(boost::format("does not support p arameterization %d")%ikparam.GetType())); default: throw openrave_exception(str(boost::format("does not support p arameterization %d")%ikparam.GetType()));
} }
return I; return I;
} }
} }
#include <openrave/plugininfo.h> #include <openrave/plugininfo.h>
#include <openrave/interface.h> #include <openrave/interface.h>
#include <openrave/spacesampler.h>
#include <openrave/kinbody.h> #include <openrave/kinbody.h>
#include <openrave/trajectory.h> #include <openrave/trajectory.h>
#include <openrave/problems.h> #include <openrave/module.h>
#include <openrave/collisionchecker.h> #include <openrave/collisionchecker.h>
#include <openrave/sensor.h> #include <openrave/sensor.h>
#include <openrave/robot.h> #include <openrave/robot.h>
#include <openrave/iksolver.h> #include <openrave/iksolver.h>
#include <openrave/planner.h> #include <openrave/planner.h>
#include <openrave/controller.h> #include <openrave/controller.h>
#include <openrave/physicsengine.h> #include <openrave/physicsengine.h>
#include <openrave/sensorsystem.h> #include <openrave/sensorsystem.h>
#include <openrave/viewer.h> #include <openrave/viewer.h>
#include <openrave/environment.h> #include <openrave/environment.h>
skipping to change at line 1068 skipping to change at line 1093
//@{ //@{
/// \brief Returns the a 16 character null-terminated string specifying a h ash of the interfaces used for checking changes. /// \brief Returns the a 16 character null-terminated string specifying a h ash of the interfaces used for checking changes.
inline const char* RaveGetInterfaceHash(InterfaceType type) inline const char* RaveGetInterfaceHash(InterfaceType type)
{ {
switch(type) { switch(type) {
case PT_Planner: return OPENRAVE_PLANNER_HASH; case PT_Planner: return OPENRAVE_PLANNER_HASH;
case PT_Robot: return OPENRAVE_ROBOT_HASH; case PT_Robot: return OPENRAVE_ROBOT_HASH;
case PT_SensorSystem: return OPENRAVE_SENSORSYSTEM_HASH; case PT_SensorSystem: return OPENRAVE_SENSORSYSTEM_HASH;
case PT_Controller: return OPENRAVE_CONTROLLER_HASH; case PT_Controller: return OPENRAVE_CONTROLLER_HASH;
case PT_ProblemInstance: return OPENRAVE_PROBLEM_HASH; case PT_Module: return OPENRAVE_MODULE_HASH;
case PT_InverseKinematicsSolver: return OPENRAVE_IKSOLVER_HASH; case PT_InverseKinematicsSolver: return OPENRAVE_IKSOLVER_HASH;
case PT_KinBody: return OPENRAVE_KINBODY_HASH; case PT_KinBody: return OPENRAVE_KINBODY_HASH;
case PT_PhysicsEngine: return OPENRAVE_PHYSICSENGINE_HASH; case PT_PhysicsEngine: return OPENRAVE_PHYSICSENGINE_HASH;
case PT_Sensor: return OPENRAVE_SENSOR_HASH; case PT_Sensor: return OPENRAVE_SENSOR_HASH;
case PT_CollisionChecker: return OPENRAVE_COLLISIONCHECKER_HASH; case PT_CollisionChecker: return OPENRAVE_COLLISIONCHECKER_HASH;
case PT_Trajectory: return OPENRAVE_TRAJECTORY_HASH; case PT_Trajectory: return OPENRAVE_TRAJECTORY_HASH;
case PT_Viewer: return OPENRAVE_VIEWER_HASH; case PT_Viewer: return OPENRAVE_VIEWER_HASH;
case PT_SpaceSampler: return OPENRAVE_SPACESAMPLER_HASH;
default: default:
throw openrave_exception("failed to find openrave interface type",O RE_InvalidArguments); throw openrave_exception("failed to find openrave interface type",O RE_InvalidArguments);
return NULL; return NULL;
} }
} }
/// safely casts from the base interface class to an openrave interface usi ng static_pointer_cast. /// safely casts from the base interface class to an openrave interface usi ng static_pointer_cast.
/// The reason why dynamic_pointer_cast cannot be used is because interface s might be created by different plugins, and the runtime type information w ill be different. /// The reason why dynamic_pointer_cast cannot be used is because interface s might be created by different plugins, and the runtime type information w ill be different.
template <typename T> template <typename T>
inline boost::shared_ptr<T> RaveInterfaceCast(InterfaceBasePtr pinterface) inline boost::shared_ptr<T> RaveInterfaceCast(InterfaceBasePtr pinterface)
skipping to change at line 1142 skipping to change at line 1168
/// \return a non-empty string if a file could be found. /// \return a non-empty string if a file could be found.
OPENRAVE_API std::string RaveFindDatabaseFile(const std::string& filename, bool bRead=true); OPENRAVE_API std::string RaveFindDatabaseFile(const std::string& filename, bool bRead=true);
/// \brief Explicitly initializes the global OpenRAVE state (optional). /// \brief Explicitly initializes the global OpenRAVE state (optional).
/// ///
/// Optional function to initialize openrave plugins and logging. /// Optional function to initialize openrave plugins and logging.
/// Although environment creation will automatically make sure this functio n is called, users might want /// Although environment creation will automatically make sure this functio n is called, users might want
/// explicit control of when this happens. /// explicit control of when this happens.
/// \param bLoadAllPlugins If true will load all the openrave plugins autom atically that can be found in the OPENRAVE_PLUGINS environment path /// \param bLoadAllPlugins If true will load all the openrave plugins autom atically that can be found in the OPENRAVE_PLUGINS environment path
/// \return 0 if successful, otherwise an error code /// \return 0 if successful, otherwise an error code
OPENRAVE_API int RaveInitialize(bool bLoadAllPlugins=true, DebugLevel level = Level_Info); OPENRAVE_API int RaveInitialize(bool bLoadAllPlugins=true, uint32_t level = Level_Info);
/// \brief Initializes the global state from an already loaded OpenRAVE env ironment. /// \brief Initializes the global state from an already loaded OpenRAVE env ironment.
/// ///
/// Because of shared object boundaries, it is necessary to pass the global state pointer /// Because of shared object boundaries, it is necessary to pass the global state pointer
/// around. If using plugin.h, this function is automatically called by \re f CreateInterfaceValidated. /// around. If using plugin.h, this function is automatically called by \re f CreateInterfaceValidated.
/// It is also called by and every InterfaceBase constructor. /// It is also called by and every InterfaceBase constructor.
/// \param[in] globalstate /// \param[in] globalstate
OPENRAVE_API void RaveInitializeFromState(UserDataPtr globalstate); OPENRAVE_API void RaveInitializeFromState(UserDataPtr globalstate);
/// \brief A pointer to the global openrave state /// \brief A pointer to the global openrave state
skipping to change at line 1189 skipping to change at line 1215
OPENRAVE_API bool RaveLoadPlugin(const std::string& libraryname); OPENRAVE_API bool RaveLoadPlugin(const std::string& libraryname);
/// \brief Returns true if interface can be created, otherwise false. /// \brief Returns true if interface can be created, otherwise false.
OPENRAVE_API bool RaveHasInterface(InterfaceType type, const std::string& i nterfacename); OPENRAVE_API bool RaveHasInterface(InterfaceType type, const std::string& i nterfacename);
OPENRAVE_API InterfaceBasePtr RaveCreateInterface(EnvironmentBasePtr penv, InterfaceType type,const std::string& interfacename); OPENRAVE_API InterfaceBasePtr RaveCreateInterface(EnvironmentBasePtr penv, InterfaceType type,const std::string& interfacename);
OPENRAVE_API RobotBasePtr RaveCreateRobot(EnvironmentBasePtr penv, const st d::string& name=""); OPENRAVE_API RobotBasePtr RaveCreateRobot(EnvironmentBasePtr penv, const st d::string& name="");
OPENRAVE_API PlannerBasePtr RaveCreatePlanner(EnvironmentBasePtr penv, cons t std::string& name); OPENRAVE_API PlannerBasePtr RaveCreatePlanner(EnvironmentBasePtr penv, cons t std::string& name);
OPENRAVE_API SensorSystemBasePtr RaveCreateSensorSystem(EnvironmentBasePtr penv, const std::string& name); OPENRAVE_API SensorSystemBasePtr RaveCreateSensorSystem(EnvironmentBasePtr penv, const std::string& name);
OPENRAVE_API ControllerBasePtr RaveCreateController(EnvironmentBasePtr penv , const std::string& name); OPENRAVE_API ControllerBasePtr RaveCreateController(EnvironmentBasePtr penv , const std::string& name);
OPENRAVE_API ProblemInstancePtr RaveCreateProblem(EnvironmentBasePtr penv, OPENRAVE_API ModuleBasePtr RaveCreateModule(EnvironmentBasePtr penv, const
const std::string& name); std::string& name);
OPENRAVE_API ProblemInstancePtr RaveCreateProblemInstance(EnvironmentBasePt OPENRAVE_API ModuleBasePtr RaveCreateProblem(EnvironmentBasePtr penv, const
r penv, const std::string& name); std::string& name);
OPENRAVE_API ModuleBasePtr RaveCreateProblemInstance(EnvironmentBasePtr pen
v, const std::string& name);
OPENRAVE_API IkSolverBasePtr RaveCreateIkSolver(EnvironmentBasePtr penv, co nst std::string& name); OPENRAVE_API IkSolverBasePtr RaveCreateIkSolver(EnvironmentBasePtr penv, co nst std::string& name);
OPENRAVE_API PhysicsEngineBasePtr RaveCreatePhysicsEngine(EnvironmentBasePt r penv, const std::string& name); OPENRAVE_API PhysicsEngineBasePtr RaveCreatePhysicsEngine(EnvironmentBasePt r penv, const std::string& name);
OPENRAVE_API SensorBasePtr RaveCreateSensor(EnvironmentBasePtr penv, const std::string& name); OPENRAVE_API SensorBasePtr RaveCreateSensor(EnvironmentBasePtr penv, const std::string& name);
OPENRAVE_API CollisionCheckerBasePtr RaveCreateCollisionChecker(Environment BasePtr penv, const std::string& name); OPENRAVE_API CollisionCheckerBasePtr RaveCreateCollisionChecker(Environment BasePtr penv, const std::string& name);
OPENRAVE_API ViewerBasePtr RaveCreateViewer(EnvironmentBasePtr penv, const std::string& name); OPENRAVE_API ViewerBasePtr RaveCreateViewer(EnvironmentBasePtr penv, const std::string& name);
OPENRAVE_API SpaceSamplerBasePtr RaveCreateSpaceSampler(EnvironmentBasePtr penv, const std::string& name);
OPENRAVE_API KinBodyPtr RaveCreateKinBody(EnvironmentBasePtr penv, const s td::string& name=""); OPENRAVE_API KinBodyPtr RaveCreateKinBody(EnvironmentBasePtr penv, const s td::string& name="");
/// \brief Return an empty trajectory instance initialized to nDOF degrees of freedom. Will be deprecated soon /// \brief Return an empty trajectory instance initialized to nDOF degrees of freedom. Will be deprecated soon
OPENRAVE_API TrajectoryBasePtr RaveCreateTrajectory(EnvironmentBasePtr penv , int nDOF); OPENRAVE_API TrajectoryBasePtr RaveCreateTrajectory(EnvironmentBasePtr penv , int nDOF);
/// \brief Return an empty trajectory instance. /// \brief Return an empty trajectory instance.
OPENRAVE_API TrajectoryBasePtr RaveCreateTrajectory(EnvironmentBasePtr penv , const std::string& name=""); OPENRAVE_API TrajectoryBasePtr RaveCreateTrajectory(EnvironmentBasePtr penv , const std::string& name="");
/** \brief Registers a function to create an interface, this allows the int erface to be created by other modules. /** \brief Registers a function to create an interface, this allows the int erface to be created by other modules.
\param type interface type \param type interface type
\param name interface name \param name interface name
skipping to change at line 1241 skipping to change at line 1269
/// \brief Return all the created OpenRAVE environments. /// \brief Return all the created OpenRAVE environments.
OPENRAVE_API void RaveGetEnvironments(std::list<EnvironmentBasePtr>& listen vironments); OPENRAVE_API void RaveGetEnvironments(std::list<EnvironmentBasePtr>& listen vironments);
/// \brief Returns the current registered reader for the interface type/xml id /// \brief Returns the current registered reader for the interface type/xml id
/// ///
/// \throw openrave_exception Will throw with ORE_InvalidArguments if regis tered function could not be found. /// \throw openrave_exception Will throw with ORE_InvalidArguments if regis tered function could not be found.
OPENRAVE_API BaseXMLReaderPtr RaveCallXMLReader(InterfaceType type, const s td::string& xmltag, InterfaceBasePtr pinterface, const AttributesList& atts ); OPENRAVE_API BaseXMLReaderPtr RaveCallXMLReader(InterfaceType type, const s td::string& xmltag, InterfaceBasePtr pinterface, const AttributesList& atts );
//@} //@}
/// \deprecated (11/06/03), use \ref SpaceSamplerBase
OPENRAVE_API void RaveInitRandomGeneration(uint32_t seed);
/// \deprecated (11/06/03), use \ref SpaceSamplerBase
OPENRAVE_API uint32_t RaveRandomInt();
/// \deprecated (11/06/03), use \ref SpaceSamplerBase
OPENRAVE_API float RaveRandomFloat(IntervalType interval=IT_Closed);
/// \deprecated (11/06/03), use \ref SpaceSamplerBase
OPENRAVE_API double RaveRandomDouble(IntervalType interval=IT_Closed);
/// \brief separates the directories from a string and returns them in a ve ctor /// \brief separates the directories from a string and returns them in a ve ctor
inline bool RaveParseDirectories(const char* pdirs, std::vector<std::string >& vdirs) inline bool RaveParseDirectories(const char* pdirs, std::vector<std::string >& vdirs)
{ {
vdirs.resize(0); vdirs.resize(0);
if( !pdirs ) { if( !pdirs ) {
return false; return false;
} }
// search for all directories separated by ':' // search for all directories separated by ':'
std::string tmp = pdirs; std::string tmp = pdirs;
std::string::size_type pos = 0, newpos=0; std::string::size_type pos = 0, newpos=0;
skipping to change at line 1318 skipping to change at line 1355
BOOST_STATIC_ASSERT(OPENRAVE_VERSION_MAJOR>=0&&OPENRAVE_VERSION_MAJOR<=255) ; BOOST_STATIC_ASSERT(OPENRAVE_VERSION_MAJOR>=0&&OPENRAVE_VERSION_MAJOR<=255) ;
BOOST_STATIC_ASSERT(OPENRAVE_VERSION_MINOR>=0&&OPENRAVE_VERSION_MINOR<=255) ; BOOST_STATIC_ASSERT(OPENRAVE_VERSION_MINOR>=0&&OPENRAVE_VERSION_MINOR<=255) ;
BOOST_STATIC_ASSERT(OPENRAVE_VERSION_PATCH>=0&&OPENRAVE_VERSION_PATCH<=255) ; BOOST_STATIC_ASSERT(OPENRAVE_VERSION_PATCH>=0&&OPENRAVE_VERSION_PATCH<=255) ;
// register for typeof (MSVC only) // register for typeof (MSVC only)
#ifdef RAVE_REGISTER_BOOST #ifdef RAVE_REGISTER_BOOST
#include BOOST_TYPEOF_INCREMENT_REGISTRATION_GROUP() #include BOOST_TYPEOF_INCREMENT_REGISTRATION_GROUP()
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::InterfaceType) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::InterfaceType)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::UserData) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::UserData)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::ProblemInstance) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::ModuleBase)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::ControllerBase) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::ControllerBase)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::PlannerBase) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::PlannerBase)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::PlannerBase::PlannerParameters) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::PlannerBase::PlannerParameters)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::IkSolverBase) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::IkSolverBase)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::SensorBase) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::SensorBase)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::SensorBase::SensorData) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::SensorBase::SensorData)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::SensorSystemBase) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::SensorSystemBase)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::SimpleSensorSystem) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::SimpleSensorSystem)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::SimpleSensorSystem::XMLData) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::SimpleSensorSystem::XMLData)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::IkSolverBase) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::IkSolverBase)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::ViewerBase) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::ViewerBase)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::SpaceSamplerBase)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::GraphHandle) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::GraphHandle)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::IkParameterization) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::IkParameterization)
BOOST_TYPEOF_REGISTER_TEMPLATE(OpenRAVE::RaveVector, 1) BOOST_TYPEOF_REGISTER_TEMPLATE(OpenRAVE::RaveVector, 1)
BOOST_TYPEOF_REGISTER_TEMPLATE(OpenRAVE::RaveTransform, 1) BOOST_TYPEOF_REGISTER_TEMPLATE(OpenRAVE::RaveTransform, 1)
BOOST_TYPEOF_REGISTER_TEMPLATE(OpenRAVE::RaveTransformMatrix, 1) BOOST_TYPEOF_REGISTER_TEMPLATE(OpenRAVE::RaveTransformMatrix, 1)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::KinBody) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::KinBody)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::KinBody::Joint) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::KinBody::Joint)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::KinBody::Joint::MIMIC) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::KinBody::Joint::MIMIC)
BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::KinBody::Link) BOOST_TYPEOF_REGISTER_TYPE(OpenRAVE::KinBody::Link)
 End of changes. 29 change blocks. 
103 lines changed or deleted 157 lines changed or added


 physicsengine.h   physicsengine.h 
skipping to change at line 86 skipping to change at line 86
virtual bool GetLinkVelocity(KinBody::LinkConstPtr link, Vector& linear vel, Vector& angularvel) = 0; virtual bool GetLinkVelocity(KinBody::LinkConstPtr link, Vector& linear vel, Vector& angularvel) = 0;
/// \brief Sets the velocities for each link, velocities correspond to the link's coordinate system origin. /// \brief Sets the velocities for each link, velocities correspond to the link's coordinate system origin.
/// \param[out] velocities the linear and angular (axis * angular_speed ) velocities for each link. /// \param[out] velocities the linear and angular (axis * angular_speed ) velocities for each link.
virtual bool GetLinkVelocities(KinBodyConstPtr body, std::vector<std::p air<Vector,Vector> >& velocities) = 0; virtual bool GetLinkVelocities(KinBodyConstPtr body, std::vector<std::p air<Vector,Vector> >& velocities) = 0;
/// add a force at a particular position in a link /// add a force at a particular position in a link
/// \param force the direction and magnitude of the force /// \param force the direction and magnitude of the force
/// \param position in the world where the force is getting applied /// \param position in the world where the force is getting applied
/// \param bAdd if true, force is added to previous forces, otherwise i t is set /// \param bAdd if true, force is added to previous forces, otherwise i t is set
virtual bool SetBodyForce(KinBody::LinkPtr link, const Vector& force, c onst Vector& position, bool bAdd) { throw openrave_exception("PhysicsEngine Base::SetBodyForce not implemented",ORE_NotImplemented); } virtual bool SetBodyForce(KinBody::LinkPtr link, const Vector& force, c onst Vector& position, bool bAdd) OPENRAVE_DUMMY_IMPLEMENTATION;
/// adds torque to a body (absolute coords) /// adds torque to a body (absolute coords)
/// \param link the link to add a torque to /// \param link the link to add a torque to
/// \param torque torque vector /// \param torque torque vector
/// \param bAdd if true, torque is added to previous torques, otherwise it is set /// \param bAdd if true, torque is added to previous torques, otherwise it is set
virtual bool SetBodyTorque(KinBody::LinkPtr link, const Vector& torque, bool bAdd) { throw openrave_exception("PhysicsEngineBase::SetBodyTorque no t implemented",ORE_NotImplemented); } virtual bool SetBodyTorque(KinBody::LinkPtr link, const Vector& torque, bool bAdd) OPENRAVE_DUMMY_IMPLEMENTATION;
/// adds torque to a joint /// adds torque to a joint
/// \param pjoint - the joint the torque is added to /// \param pjoint - the joint the torque is added to
/// \param pTorques - the torques added to the joint. Pointer because t he joint dof can be greater than 1. /// \param pTorques - the torques added to the joint. Pointer because t he joint dof can be greater than 1.
virtual bool AddJointTorque(KinBody::JointPtr pjoint, const std::vector <dReal>& pTorques) { throw openrave_exception("PhysicsEngineBase::AddJointT orque not implemented",ORE_NotImplemented); } virtual bool AddJointTorque(KinBody::JointPtr pjoint, const std::vector <dReal>& pTorques) OPENRAVE_DUMMY_IMPLEMENTATION;
/// \param[in] link the link /// \param[in] link the link
/// \param[out] force current accumulated force on the COM of the link /// \param[out] force current accumulated force on the COM of the link
/// \param[out] torque current accumulated torque on the COM of the lin k /// \param[out] torque current accumulated torque on the COM of the lin k
virtual bool GetLinkForceTorque(KinBody::LinkConstPtr link, Vector& for ce, Vector& torque) { throw openrave_exception("PhysicsEngineBase::GetLinkF orceTorque not implemented",ORE_NotImplemented); } virtual bool GetLinkForceTorque(KinBody::LinkConstPtr link, Vector& for ce, Vector& torque) OPENRAVE_DUMMY_IMPLEMENTATION;
/// set the gravity direction /// set the gravity direction
virtual void SetGravity(const Vector& gravity) { throw openrave_excepti virtual void SetGravity(const Vector& gravity) OPENRAVE_DUMMY_IMPLEMENT
on("PhysicsEngineBase::SetGravity not implemented",ORE_NotImplemented); } ATION;
virtual Vector GetGravity() { throw openrave_exception("PhysicsEngineBa virtual Vector GetGravity() OPENRAVE_DUMMY_IMPLEMENTATION;
se::GetGravity not implemented",ORE_NotImplemented); }
/// dynamically simulate system for fTimeElapsed seconds /// dynamically simulate system for fTimeElapsed seconds
/// add torques to the joints of the body. Torques disappear after one timestep of simulation /// add torques to the joints of the body. Torques disappear after one timestep of simulation
virtual void SimulateStep(dReal fTimeElapsed)=0; virtual void SimulateStep(dReal fTimeElapsed)=0;
/// \deprecated (10/11/18) /// \deprecated (10/11/18)
virtual bool GetBodyVelocity(KinBodyConstPtr body, std::vector<Vector>& vLinearVelocities, std::vector<Vector>& vAngularVelocities) RAVE_DEPRECATE D { virtual bool GetBodyVelocity(KinBodyConstPtr body, std::vector<Vector>& vLinearVelocities, std::vector<Vector>& vAngularVelocities) RAVE_DEPRECATE D {
std::vector<std::pair<Vector,Vector> > velocities; std::vector<std::pair<Vector,Vector> > velocities;
if( !GetLinkVelocities(body, velocities) ) { if( !GetLinkVelocities(body, velocities) ) {
return false; return false;
 End of changes. 5 change blocks. 
8 lines changed or deleted 7 lines changed or added


 planner.h   planner.h 
// -*- coding: utf-8 -*- // -*- coding: utf-8 -*-
// Copyright (C) 2006-2010 Rosen Diankov (rosen.diankov@gmail.com) // Copyright (C) 2006-2011 Rosen Diankov <rosen.diankov@gmail.com>
// //
// This file is part of OpenRAVE. // This file is part of OpenRAVE.
// OpenRAVE is free software: you can redistribute it and/or modify // OpenRAVE is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by // it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or // the Free Software Foundation, either version 3 of the License, or
// at your option) any later version. // at your option) any later version.
// //
// This program is distributed in the hope that it will be useful, // This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of // but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
skipping to change at line 31 skipping to change at line 31
#define OPENRAVE_PLANNER_H #define OPENRAVE_PLANNER_H
namespace OpenRAVE { namespace OpenRAVE {
/** \brief <b>[interface]</b> Planner interface that generates trajectories for the robot to follow around the environment. See \ref arch_planner. /** \brief <b>[interface]</b> Planner interface that generates trajectories for the robot to follow around the environment. See \ref arch_planner.
\ingroup interfaces \ingroup interfaces
*/ */
class OPENRAVE_API PlannerBase : public InterfaceBase class OPENRAVE_API PlannerBase : public InterfaceBase
{ {
public: public:
/// Options for constraint planning. typedef std::list< std::vector<dReal> > ConfigurationList;
enum ConstraintSettings { typedef boost::shared_ptr< PlannerBase::ConfigurationList > Configurati
CS_TimeBackward=1, ///< if not specified, time is forward onListPtr;
};
/** \brief Describes a common and serializable interface for planning p arameters. /** \brief Describes a common and serializable interface for planning p arameters.
The class is serializable to XML, so can be loaded from file or pas sed around the network. The class is serializable to XML, so can be loaded from file or pas sed around the network.
If extra parameters need to be specified, derive from this class an d If extra parameters need to be specified, derive from this class an d
- add the extra tags to PlannerParameters::_vXMLParameters - add the extra tags to PlannerParameters::_vXMLParameters
- override PlannerParameters::startElement and PlannerParameters::e ndElement for processing - override PlannerParameters::startElement and PlannerParameters::e ndElement for processing
- possibly override the PlannerParameters::characters - possibly override the PlannerParameters::characters
Also allows the parameters and descriptions to be serialized to reS tructuredText for documentation purposes. Also allows the parameters and descriptions to be serialized to reS tructuredText for documentation purposes.
skipping to change at line 59 skipping to change at line 57
PlannerParameters(); PlannerParameters();
virtual ~PlannerParameters() {} virtual ~PlannerParameters() {}
/// tries to copy data from one set of parameters to another in the safest manner. /// tries to copy data from one set of parameters to another in the safest manner.
/// First serializes the data of the right hand into a string, then initializes the current parameters via >> /// First serializes the data of the right hand into a string, then initializes the current parameters via >>
/// pointers to functions are copied directly /// pointers to functions are copied directly
virtual PlannerParameters& operator=(const PlannerParameters& r); virtual PlannerParameters& operator=(const PlannerParameters& r);
virtual void copy(boost::shared_ptr<PlannerParameters const> r); virtual void copy(boost::shared_ptr<PlannerParameters const> r);
/// sets up the planner parameters to use the active joints of the robot /// sets up the planner parameters to use the active joints of the robot
void SetRobotActiveJoints(RobotBasePtr robot); virtual void SetRobotActiveJoints(RobotBasePtr robot);
/// \brief Cost function on the state pace (optional). /// \brief Cost function on the state pace (optional).
/// ///
/// cost = costfn(config) /// cost = _costfn(config)
/// \param cost the cost of being in the current state /// \param cost the cost of being in the current state
boost::function<dReal(const std::vector<dReal>&)> _costfn; typedef boost::function<dReal(const std::vector<dReal>&)> CostFn;
CostFn _costfn;
/// \brief Goal heuristic function. /// \brief Goal heuristic function.(optional)
/// ///
/// goal is complete when returns 0 (optional) /// distance = _goalfn(config)
/// distance = goalfn(config) ///
/// Goal is complete when returns 0
/// \param distance - distance to closest goal /// \param distance - distance to closest goal
boost::function<dReal(const std::vector<dReal>&)> _goalfn; typedef boost::function<dReal(const std::vector<dReal>&)> GoalFn;
GoalFn _goalfn;
/// optional, Distance metric between configuration spaces, two con /// \brief optional, Distance metric between configuration spaces,
figurations are considered the same when this returns 0: distmetric(config1 two configurations are considered the same when this returns 0: distmetric(
,config2) config1,config2)
boost::function<dReal(const std::vector<dReal>&, const std::vector< typedef boost::function<dReal(const std::vector<dReal>&, const std:
dReal>&)> _distmetricfn; :vector<dReal>&)> DistMetricFn;
DistMetricFn _distmetricfn;
/// \brief Filters the current robot configurations (optional). /** \brief Checks that all the constraints are satisfied between tw
/// o configurations.
/// optional, used to maintain certains a movement from a src robot
configuration to robot configuration: The simplest and most fundamental constraint is line-collision
/// success = _constraintfn(vprevconf,vnewconf,settings) checking. The robot goes from q0 to q1.
/// When called, vnewconf is guaranteed to be set on the robot. The
function returns true if vnewconf is accepted. success = _checkpathconstraints(q0,q1,interval,configurations)
/// Note that the function can also modify vnewconf (like projectin
g onto a constraint manifold), When called, q0 is guaranteed to be set on the robot.
/// therefore the planner will use the new vnewconf value after thi The function returns true if the path to q1 satisfies all the c
s call. onstraints of the planner.
/// \param vprevconf is the configuration the robot is coming from If q0==q1, and interval==IT_OpenStart or IT_OpenEnd, then only
/// \param vnewconf is the configuration the robot is current at, w one configuration should be checked. It is recommended to use IT_OpenStart.
hich needs to be filtered Because this function can internally use neighstatefn, need to
/// \param settings options specified in ConstraingSettings make sure that Q0->Q1 is going from initial to goal direction.
boost::function<bool(const std::vector<dReal>&, std::vector<dReal>&
, int)> _constraintfn; \param q0 is the configuration the robot is coming from (curren
tly set).
\param q1 is the configuration the robot should move to.
\param interval Specifies whether to check the end points of th
e interval for constraints
\param configurations Optional argument that will hold the inte
rmediate configuraitons checked between q0 and q1 configurations. The appen
ded configurations will be all valid and in free space. They are appended a
fter the items already stored on the list.
*/
typedef boost::function<bool(const std::vector<dReal>&, const std::
vector<dReal>&, IntervalType, PlannerBase::ConfigurationListPtr)> CheckPath
ConstraintFn;
CheckPathConstraintFn _checkpathconstraintsfn;
/// \brief Samples a random configuration (mandatory) /// \brief Samples a random configuration (mandatory)
/// ///
/// The dimension of the returned sample is the dimension of the co nfiguration space. /// The dimension of the returned sample is the dimension of the co nfiguration space.
/// success = samplefn(newsample) /// success = samplefn(newsample)
boost::function<bool(std::vector<dReal>&)> _samplefn; typedef boost::function<bool(std::vector<dReal>&)> SampleFn;
SampleFn _samplefn;
/// \brief Samples a valid goal configuration (optional). /// \brief Samples a valid goal configuration (optional).
/// ///
/// If valid, the function should be called /// If valid, the function should be called
/// at every iteration. Any type of goal sampling probabilities and /// at every iteration. Any type of sampling probabilities and cond
conditions can be encoded inside the function. itions can be encoded inside the function.
// The dimension of the returned sample is the dimension of the con /// The dimension of the returned sample is the dimension of the co
figuration space. nfiguration space.
// success = samplegoalfn(newsample) /// success = samplegoalfn(newsample)
boost::function<bool(std::vector<dReal>&)> _samplegoalfn; typedef boost::function<bool(std::vector<dReal>&)> SampleGoalFn;
SampleGoalFn _samplegoalfn;
/// \brief Returns a random configuration around a neighborhood (op tional). /// \brief Samples a valid initial configuration (optional).
/// ///
/// _sampleneighfn(newsample,pCurSample,fRadius) /// If valid, the function should be called
/// \param pCurSample - the neighborhood to sample around /// at every iteration. Any type of sampling probabilities and cond
/// \param fRadius - specifies the max distance of sampling. The h itions can be encoded inside the function.
igher the value, the farther the samples will go /// The dimension of the returned sample is the dimension of the co
/// The distance metric can be arbitrary, but is usuall nfiguration space.
y PlannerParameters::pdistmetric. /// success = sampleinitialfn(newsample)
/// \return if sample was successfully generated return true, other typedef boost::function<bool(std::vector<dReal>&)> SampleInitialFn;
wise false SampleInitialFn _sampleinitialfn;
boost::function<bool(std::vector<dReal>&, const std::vector<dReal>&
, dReal)> _sampleneighfn; /** \brief Returns a random configuration around a neighborhood (op
tional).
_sampleneighfn(newsample,pCurSample,fRadius)
\param pCurSample - the neighborhood to sample around
\param fRadius - specifies the max distance of sampling. The h
igher the value, the farther the samples will go
The distance metric can be arbitrary, but is
usually PlannerParameters::pdistmetric.
\return if sample was successfully generated return true, other
wise false
*/
typedef boost::function<bool(std::vector<dReal>&, const std::vector
<dReal>&, dReal)> SampleNeighFn;
SampleNeighFn _sampleneighfn;
/// \brief Sets the state of the robot. Default is active robot joi nts (mandatory). /// \brief Sets the state of the robot. Default is active robot joi nts (mandatory).
boost::function<void(const std::vector<dReal>&)> _setstatefn; typedef boost::function<void(const std::vector<dReal>&)> SetStateFn
;
SetStateFn _setstatefn;
/// \brief Gets the state of the robot. Default is active robot joi nts (mandatory). /// \brief Gets the state of the robot. Default is active robot joi nts (mandatory).
boost::function<void(std::vector<dReal>&)> _getstatefn; typedef boost::function<void(std::vector<dReal>&)> GetStateFn;
/// \brief Computes the difference of two states. GetStateFn _getstatefn;
///
/// An explicit difference function is necessary for correct interp
olation when there are circular joints.
/// Default is regular subtraction.
/// _diffstatefn(q1,q2) -> q1 -= q2
boost::function<void(std::vector<dReal>&,const std::vector<dReal>&)
> _diffstatefn;
/// to specify multiple goal configurations, put them into the vect /** \brief Computes the difference of two states.
or in series (note: not all planners support multiple goals)
std::vector<dReal> vinitialconfig, vgoalconfig;
/// goal transformation in workspace, can be the end effector or ab _diffstatefn(q1,q2) -> q1 -= q2
solute transformation ,etc
boost::shared_ptr<Transform> _tWorkspaceGoal;
/// the absolute limits of the configuration space. An explicit difference function is necessary for correct interp
std::vector<dReal> _vConfigLowerLimit,_vConfigUpperLimit; olation when there are circular joints.
Default is regular subtraction.
*/
typedef boost::function<void(std::vector<dReal>&,const std::vector<
dReal>&)> DiffStateFn;
DiffStateFn _diffstatefn;
/// the discretization resolution of each dimension of the configur /** \brief Adds a delta state to a curent state, acting like a next
ation space -nearest-neighbor function along a given direction.
success = _neighstatefn(q,qdelta,fromgoal) -> q = Filter(q+qdel
ta)
\param q the current state
\param qdelta the delta to add
\param fromgoal 1 if q is coming from a goal state, 0 if it is
coming from an initial state
In RRTs this is used for the extension operation. The new state
is stored in the first parameter q.
Note that the function can also add a filter to the final desti
nation (like projecting onto a constraint manifold).
*/
typedef boost::function<bool(std::vector<dReal>&,const std::vector<
dReal>&, int)> NeighStateFn;
NeighStateFn _neighstatefn;
/// to specify multiple initial or goal configurations, put them in
to the vector in series
/// (note: not all planners support multiple goals)
std::vector<dReal> vinitialconfig, vgoalconfig;
/// \brief the absolute limits of the configuration space.
std::vector<dReal> _vConfigLowerLimit, _vConfigUpperLimit;
/// \brief the discretization resolution of each dimension of the c
onfiguration space
std::vector<dReal> _vConfigResolution; std::vector<dReal> _vConfigResolution;
/// a minimum distance between neighbors when searching. If 0 or le /** \brief a discretization between the path that connects two conf
ss, planner chooses best step length igurations
This length represents how dense the samples get distributed ac
ross the configuration space.
It represents the maximum distance between neighbors when addin
g new configuraitons.
If 0 or less, planner chooses best step length.
*/
dReal _fStepLength; dReal _fStepLength;
/// maximum number of iterations before the planner gives up. If 0 or less, planner chooses best iterations. /// \brief maximum number of iterations before the planner gives up . If 0 or less, planner chooses best iterations.
int _nMaxIterations; int _nMaxIterations;
/// specifies the planner that will perform the post-processing pat /// \brief Specifies the planner that will perform the post-process
h smoothing before returning. ing path smoothing before returning.
///
/// If empty, will not path smooth the returned trajectories (used to measure algorithm time) /// If empty, will not path smooth the returned trajectories (used to measure algorithm time)
std::string _sPathOptimizationPlanner; std::string _sPathOptimizationPlanner;
/// The serialized planner parameters to pass to the path optimizer
. For example: /// \brief The serialized planner parameters to pass to the path op
/// std::stringstream(_sPathOptimizationParameters) >> _parameters; timizer.
///
/// For example: std::stringstream(_sPathOptimizationParameters) >>
_parameters;
std::string _sPathOptimizationParameters; std::string _sPathOptimizationParameters;
/// extra parameters data that does not fit within this planner par ameters structure, but is still important not to lose all the information. /// \brief Extra parameters data that does not fit within this plan ner parameters structure, but is still important not to lose all the inform ation.
std::string _sExtraParameters; std::string _sExtraParameters;
/// \return the degrees of freedom of the planning configuration sp ace /// \brief Return the degrees of freedom of the planning configurat ion space
virtual int GetDOF() const { return (int)_vConfigLowerLimit.size(); } virtual int GetDOF() const { return (int)_vConfigLowerLimit.size(); }
protected: protected:
inline boost::shared_ptr<PlannerBase::PlannerParameters> shared_par
ameters() { return boost::static_pointer_cast<PlannerBase::PlannerParameter
s>(shared_from_this()); }
inline boost::shared_ptr<PlannerBase::PlannerParameters const > sha
red_parameters_const() const { return boost::static_pointer_cast<PlannerBas
e::PlannerParameters const>(shared_from_this()); }
/// output the planner parameters in a string (in XML format) /// output the planner parameters in a string (in XML format)
/// don't use PlannerParameters as a tag! /// don't use PlannerParameters as a tag!
virtual bool serialize(std::ostream& O) const; virtual bool serialize(std::ostream& O) const;
//@{ XML parsing functions, parses the default parameters //@{ XML parsing functions, parses the default parameters
virtual ProcessElement startElement(const std::string& name, const AttributesList& atts); virtual ProcessElement startElement(const std::string& name, const AttributesList& atts);
virtual bool endElement(const std::string& name); virtual bool endElement(const std::string& name);
virtual void characters(const std::string& ch); virtual void characters(const std::string& ch);
std::stringstream _ss; ///< holds the data read by characters std::stringstream _ss; ///< holds the data read by characters
boost::shared_ptr<std::stringstream> _sslocal; boost::shared_ptr<std::stringstream> _sslocal;
skipping to change at line 181 skipping to change at line 232
PlannerParameters(const PlannerParameters& r) : XMLReadable("") { B OOST_ASSERT(0); } PlannerParameters(const PlannerParameters& r) : XMLReadable("") { B OOST_ASSERT(0); }
BaseXMLReaderPtr __pcurreader; ///< temporary reader BaseXMLReaderPtr __pcurreader; ///< temporary reader
std::string __processingtag; std::string __processingtag;
int _plannerparametersdepth; int _plannerparametersdepth;
/// outputs the data and surrounds it with \verbatim <PlannerParame ters> \endverbatim tags /// outputs the data and surrounds it with \verbatim <PlannerParame ters> \endverbatim tags
friend OPENRAVE_API std::ostream& operator<<(std::ostream& O, const PlannerParameters& v); friend OPENRAVE_API std::ostream& operator<<(std::ostream& O, const PlannerParameters& v);
/// expects \verbatim <PlannerParameters> \endverbatim to be the fi rst token. Parses stream until \verbatim </PlannerParameters> \endverbatim reached /// expects \verbatim <PlannerParameters> \endverbatim to be the fi rst token. Parses stream until \verbatim </PlannerParameters> \endverbatim reached
friend OPENRAVE_API std::istream& operator>>(std::istream& I, Plann erParameters& v); friend OPENRAVE_API std::istream& operator>>(std::istream& I, Plann erParameters& v);
}; };
typedef boost::shared_ptr<PlannerParameters> PlannerParametersPtr; typedef boost::shared_ptr<PlannerBase::PlannerParameters> PlannerParame
typedef boost::shared_ptr<PlannerParameters const> PlannerParametersCon tersPtr;
stPtr; typedef boost::shared_ptr<PlannerBase::PlannerParameters const> Planner
ParametersConstPtr;
typedef boost::weak_ptr<PlannerBase::PlannerParameters> PlannerParamete
rsWeakPtr;
PlannerBase(EnvironmentBasePtr penv) : InterfaceBase(PT_Planner, penv) {} PlannerBase(EnvironmentBasePtr penv) : InterfaceBase(PT_Planner, penv) {}
virtual ~PlannerBase() {} virtual ~PlannerBase() {}
/// \return the static interface type this class points to (used for sa fe casting) /// \return the static interface type this class points to (used for sa fe casting)
static inline InterfaceType GetInterfaceTypeStatic() { return PT_Planne r; } static inline InterfaceType GetInterfaceTypeStatic() { return PT_Planne r; }
/// \brief Setup scene, robot, and properties of the plan, and reset al l internal structures. /// \brief Setup scene, robot, and properties of the plan, and reset al l internal structures.
/// \param probot The robot will be planning for. /// \param probot The robot will be planning for.
/// \param pparams The parameters of the planner, any class derived fro m PlannerParameters can be passed. The planner should copy these parameters for future instead of storing the pointer. /// \param pparams The parameters of the planner, any class derived fro m PlannerParameters can be passed. The planner should copy these parameters for future instead of storing the pointer.
 End of changes. 28 change blocks. 
85 lines changed or deleted 162 lines changed or added


 plugin.h   plugin.h 
skipping to change at line 60 skipping to change at line 60
Only use when \ref rave/plugin.h is included. Only use when \ref rave/plugin.h is included.
\param[out] info Holds information on what services this plugin provide s. \param[out] info Holds information on what services this plugin provide s.
*/ */
void GetPluginAttributesValidated(OpenRAVE::PLUGININFO& info); void GetPluginAttributesValidated(OpenRAVE::PLUGININFO& info);
/// \brief <b>[export]</b> Definition of a plugin export. Requires \ref Cre ateInterfaceValidated to be defined. /// \brief <b>[export]</b> Definition of a plugin export. Requires \ref Cre ateInterfaceValidated to be defined.
/// \ingroup plugin_exports /// \ingroup plugin_exports
OPENRAVE_PLUGIN_API OpenRAVE::InterfaceBasePtr OpenRAVECreateInterface(Open RAVE::InterfaceType type, const std::string& name, const char* interfacehas h, const char* envhash, OpenRAVE::EnvironmentBasePtr penv) OPENRAVE_PLUGIN_API OpenRAVE::InterfaceBasePtr OpenRAVECreateInterface(Open RAVE::InterfaceType type, const std::string& name, const char* interfacehas h, const char* envhash, OpenRAVE::EnvironmentBasePtr penv)
{ {
if( strcmp(interfacehash,OpenRAVE::RaveGetInterfaceHash(type)) ) { if( strcmp(interfacehash,OpenRAVE::RaveGetInterfaceHash(type)) ) {
throw OpenRAVE::openrave_exception(str(boost::format("bad interface %s hash")%RaveGetInterfaceName(type)),OpenRAVE::ORE_InvalidInterfaceHash); throw OPENRAVE_EXCEPTION_FORMAT("bad interface %s hash: %s!=%s",Rav eGetInterfaceName(type)%interfacehash%OpenRAVE::RaveGetInterfaceHash(type), OpenRAVE::ORE_InvalidInterfaceHash);
} }
if( !penv ) { if( !penv ) {
throw OpenRAVE::openrave_exception("bad environment",OpenRAVE::ORE_ InvalidArguments); throw OPENRAVE_EXCEPTION_FORMAT0("need to set environment",OpenRAVE ::ORE_InvalidArguments);
} }
if( strcmp(envhash,OPENRAVE_ENVIRONMENT_HASH) ) { if( strcmp(envhash,OPENRAVE_ENVIRONMENT_HASH) ) {
throw OpenRAVE::openrave_exception("bad environment hash",OpenRAVE: :ORE_InvalidPlugin); throw OPENRAVE_EXCEPTION_FORMAT("bad environment hash: %s!=%s",envh ash%OPENRAVE_ENVIRONMENT_HASH,OpenRAVE::ORE_InvalidPlugin);
} }
OpenRAVE::RaveInitializeFromState(penv->GlobalState()); // make sure gl obal state is set OpenRAVE::RaveInitializeFromState(penv->GlobalState()); // make sure gl obal state is set
std::stringstream sinput(name); std::stringstream sinput(name);
std::string interfacename; std::string interfacename;
sinput >> interfacename; sinput >> interfacename;
std::transform(interfacename.begin(), interfacename.end(), interfacenam e.begin(), ::tolower); std::transform(interfacename.begin(), interfacename.end(), interfacenam e.begin(), ::tolower);
return CreateInterfaceValidated(type,interfacename,sinput,penv); return CreateInterfaceValidated(type,interfacename,sinput,penv);
} }
/// \brief \b <b>[export]</b> Definition of a plugin export. Requires \ref GetPluginAttributesValidated to be defined. /// \brief \b <b>[export]</b> Definition of a plugin export. Requires \ref GetPluginAttributesValidated to be defined.
/// \ingroup plugin_exports /// \ingroup plugin_exports
OPENRAVE_PLUGIN_API void OpenRAVEGetPluginAttributes(OpenRAVE::PLUGININFO* pinfo, int size, const char* infohash) OPENRAVE_PLUGIN_API void OpenRAVEGetPluginAttributes(OpenRAVE::PLUGININFO* pinfo, int size, const char* infohash)
{ {
if( pinfo == NULL ) { if( pinfo == NULL ) {
throw OpenRAVE::openrave_exception("bad data",OpenRAVE::ORE_Invalid Arguments); throw OPENRAVE_EXCEPTION_FORMAT0("bad data",OpenRAVE::ORE_InvalidAr guments);
} }
if( size != sizeof(OpenRAVE::PLUGININFO) ) { if( size != sizeof(OpenRAVE::PLUGININFO) ) {
throw OpenRAVE::openrave_exception(str(boost::format("bad plugin in fo sizes %d != %d")%size%sizeof(OpenRAVE::PLUGININFO)),OpenRAVE::ORE_Invali dPlugin); throw OPENRAVE_EXCEPTION_FORMAT("bad plugin info sizes %d != %d", s ize%sizeof(OpenRAVE::PLUGININFO),OpenRAVE::ORE_InvalidPlugin);
} }
if( strcmp(infohash,OPENRAVE_PLUGININFO_HASH) ) { if( strcmp(infohash,OPENRAVE_PLUGININFO_HASH) ) {
throw OpenRAVE::openrave_exception("bad plugin info hash",OpenRAVE: :ORE_InvalidPlugin); throw OPENRAVE_EXCEPTION_FORMAT0("bad plugin info hash",OpenRAVE::O RE_InvalidPlugin);
} }
GetPluginAttributesValidated(*pinfo); GetPluginAttributesValidated(*pinfo);
pinfo->version = OPENRAVE_VERSION; pinfo->version = OPENRAVE_VERSION;
} }
/// \brief \b <b>[export]</b> Stub function to be defined by plugin that in cludes \ref rave/plugin.h. /// \brief \b <b>[export]</b> Stub function to be defined by plugin that in cludes \ref rave/plugin.h.
/// \ingroup plugin_exports /// \ingroup plugin_exports
OPENRAVE_PLUGIN_API void DestroyPlugin(); OPENRAVE_PLUGIN_API void DestroyPlugin();
//@} //@}
 End of changes. 6 change blocks. 
6 lines changed or deleted 6 lines changed or added


 robot.h   robot.h 
skipping to change at line 26 skipping to change at line 26
// along with this program. If not, see <http://www.gnu.org/licenses/>. // along with this program. If not, see <http://www.gnu.org/licenses/>.
/** \file robot.h /** \file robot.h
\brief Base robot and manipulator description. \brief Base robot and manipulator description.
*/ */
#ifndef RAVE_ROBOT_H #ifndef RAVE_ROBOT_H
#define RAVE_ROBOT_H #define RAVE_ROBOT_H
namespace OpenRAVE { namespace OpenRAVE {
/** \brief <b>[interface]</b> A robot is a kinematic body that has attached manipulators, sensors, and controllers. See \ref arch_robot. /** \brief <b>[interface]</b> A robot is a kinematic body that has attached manipulators, sensors, and controllers. <b>Methods not multi-thread safe.< /b> See \ref arch_robot.
\ingroup interfaces \ingroup interfaces
*/ */
class OPENRAVE_API RobotBase : public KinBody class OPENRAVE_API RobotBase : public KinBody
{ {
public: public:
/// \brief Defines a chain of joints for an arm and set of joints for a gripper. Simplifies operating with them. /// \brief Defines a chain of joints for an arm and set of joints for a gripper. Simplifies operating with them.
class OPENRAVE_API Manipulator : public boost::enable_shared_from_this< Manipulator> class OPENRAVE_API Manipulator : public boost::enable_shared_from_this< Manipulator>
{ {
Manipulator(RobotBasePtr probot); Manipulator(RobotBasePtr probot);
Manipulator(const Manipulator& r); Manipulator(const Manipulator& r);
Manipulator(RobotBasePtr probot, const Manipulator& r); Manipulator(RobotBasePtr probot, const Manipulator& r);
public: public:
virtual ~Manipulator(); virtual ~Manipulator();
/// \brief Return the transformation of the end effector (manipulat or frame). /// \brief Return the transformation of the end effector (manipulat or frame).
/// ///
/// All inverse kinematics and grasping queries are specifying this frame. /// All inverse kinematics and grasping queries are specifying this frame.
virtual Transform GetEndEffectorTransform() const; virtual Transform GetTransform() const;
virtual Transform GetEndEffectorTransform() const { return GetTrans
form(); }
virtual const std::string& GetName() const { return _name; } virtual const std::string& GetName() const { return _name; }
virtual RobotBasePtr GetRobot() const { return RobotBasePtr(_probot ); } virtual RobotBasePtr GetRobot() const { return RobotBasePtr(_probot ); }
/// \brief Sets the ik solver and initializes it with the current m anipulator. /// \brief Sets the ik solver and initializes it with the current m anipulator.
/// ///
/// Due to complications with translation,rotation,direction,and ra y ik, /// Due to complications with translation,rotation,direction,and ra y ik,
/// the ik solver should take into account the grasp transform (_tG rasp) internally. /// the ik solver should take into account the grasp transform (_tG rasp) internally.
/// The actual ik primitives are transformed into the base frame on ly. /// The actual ik primitives are transformed into the base frame on ly.
virtual bool SetIkSolver(IkSolverBasePtr iksolver); virtual bool SetIkSolver(IkSolverBasePtr iksolver);
/// \brief Returns the currently set ik solver /// \brief Returns the currently set ik solver
virtual IkSolverBasePtr GetIkSolver() const { return _pIkSolver; } virtual IkSolverBasePtr GetIkSolver() const { return _pIkSolver; }
/// \deprecated (10/07/29)
virtual bool SetIKSolver(IkSolverBasePtr iksolver) RAVE_DEPRECATED
{ return SetIkSolver(iksolver); }
/// \deprecated (10/07/29)
virtual bool InitIKSolver() RAVE_DEPRECATED;
/// \deprecated (10/07/29)
virtual const std::string& GetIKSolverName() const RAVE_DEPRECATED
{ return _strIkSolver; }
/// \deprecated (10/07/29)
virtual bool HasIKSolver() const RAVE_DEPRECATED { return !!_pIkSol
ver; }
/// \deprecated (11/02/08) use GetIkSolver()->GetNumFreeParameters( ) /// \deprecated (11/02/08) use GetIkSolver()->GetNumFreeParameters( )
virtual int GetNumFreeParameters() const RAVE_DEPRECATED; virtual int GetNumFreeParameters() const RAVE_DEPRECATED;
/// \deprecated (11/02/08) use GetIkSolver()->GetFreeParameters() /// \deprecated (11/02/08) use GetIkSolver()->GetFreeParameters()
virtual bool GetFreeParameters(std::vector<dReal>& vFreeParameters) const RAVE_DEPRECATED; virtual bool GetFreeParameters(std::vector<dReal>& vFreeParameters) const RAVE_DEPRECATED;
/// the base used for the iksolver /// \brief the base used for the iksolver
virtual LinkPtr GetBase() const { return _pBase; } virtual LinkPtr GetBase() const { return _pBase; }
/// the end effector link (used to define workspace distance) /// \brief the end effector link (used to define workspace distance )
virtual LinkPtr GetEndEffector() const { return _pEndEffector; } virtual LinkPtr GetEndEffector() const { return _pEndEffector; }
/// \return transform with respect to end effector defining the gra sp coordinate system /// \brief Return transform with respect to end effector defining t he grasp coordinate system
virtual Transform GetGraspTransform() const { return _tGrasp; } virtual Transform GetGraspTransform() const { return _tGrasp; }
/// \brief Gripper indices of the joints that the manipulator cont rols. /// \brief Gripper indices of the joints that the manipulator cont rols.
virtual const std::vector<int>& GetGripperIndices() const { return __vgripperdofindices; } virtual const std::vector<int>& GetGripperIndices() const { return __vgripperdofindices; }
/// \deprecated (10/07/22) see GetGripperIndices()
virtual const std::vector<int>& GetGripperJoints() const RAVE_DEPRE
CATED { return __vgripperdofindices; }
/// \deprecated (10/07/22) see GetArmIndices()
virtual const std::vector<int>& GetArmJoints() const RAVE_DEPRECATE
D { return __varmdofindices; }
/// \brief Return the indices of the DOFs of the arm (used for IK, etc). /// \brief Return the indices of the DOFs of the arm (used for IK, etc).
/// ///
/// Usually the DOF indices from pBase to pEndEffector /// Usually the DOF indices from pBase to pEndEffector
virtual const std::vector<int>& GetArmIndices() const { return __va rmdofindices; } virtual const std::vector<int>& GetArmIndices() const { return __va rmdofindices; }
/// \brief return the normal direction to move joints to 'close' th e hand /// \brief return the normal direction to move joints to 'close' th e hand
virtual const std::vector<dReal>& GetClosingDirection() const { ret urn _vClosingDirection; } virtual const std::vector<dReal>& GetClosingDirection() const { ret urn _vClosingDirection; }
/// \deprecated (10/07/01) see GetDirection() /// \brief direction of palm/head/manipulator used for approaching.
virtual Vector GetPalmDirection() const RAVE_DEPRECATED { return _v defined inside the manipulator/grasp coordinate system
direction; }
/// direction of palm/head/manipulator used for approaching inside
the grasp coordinate system
virtual Vector GetDirection() const { return _vdirection; } virtual Vector GetDirection() const { return _vdirection; }
/// will find a close solution to the current robot's joint values. /// \brief Find a close solution to the current robot's joint value
The function is a wrapper around the IkSolver interface. s.
///
/// The function is a wrapper around the IkSolver interface.
/// Note that the solution returned is not guaranteed to be the clo sest solution. In order to compute that, will have to /// Note that the solution returned is not guaranteed to be the clo sest solution. In order to compute that, will have to
/// compute all the ik solutions using FindIKSolutions. /// compute all the ik solutions using FindIKSolutions.
/// \param goal The transformation of the end-effector in the globa l coord system /// \param param The transformation of the end-effector in the glob al coord system
/// \param solution Will be of size GetArmIndices().size() and cont ain the best solution /// \param solution Will be of size GetArmIndices().size() and cont ain the best solution
/// \param[in] filteroptions A bitmask of \ref IkFilterOptions valu es controlling what is checked for each ik solution. /// \param[in] filteroptions A bitmask of \ref IkFilterOptions valu es controlling what is checked for each ik solution.
virtual bool FindIKSolution(const IkParameterization& goal, std::ve virtual bool FindIKSolution(const IkParameterization& param, std::v
ctor<dReal>& solution, int filteroptions) const; ector<dReal>& solution, int filteroptions) const;
virtual bool FindIKSolution(const IkParameterization& goal, const s virtual bool FindIKSolution(const IkParameterization& param, const
td::vector<dReal>& vFreeParameters, std::vector<dReal>& solution, int filte std::vector<dReal>& vFreeParameters, std::vector<dReal>& solution, int filt
roptions) const; eroptions) const;
/// will find all the IK solutions for the given end effector trans /// \brief Find all the IK solutions for the given end effector tra
form nsform
/// \param goal The transformation of the end-effector in the globa ///
l coord system /// \param param The transformation of the end-effector in the glob
al coord system
/// \param solutions An array of all solutions, each element in sol utions is of size GetArmIndices().size() /// \param solutions An array of all solutions, each element in sol utions is of size GetArmIndices().size()
/// \param[in] filteroptions A bitmask of \ref IkFilterOptions valu es controlling what is checked for each ik solution. /// \param[in] filteroptions A bitmask of \ref IkFilterOptions valu es controlling what is checked for each ik solution.
virtual bool FindIKSolutions(const IkParameterization& goal, std::v virtual bool FindIKSolutions(const IkParameterization& param, std::
ector<std::vector<dReal> >& solutions, int filteroptions) const; vector<std::vector<dReal> >& solutions, int filteroptions) const;
virtual bool FindIKSolutions(const IkParameterization& goal, const virtual bool FindIKSolutions(const IkParameterization& param, const
std::vector<dReal>& vFreeParameters, std::vector<std::vector<dReal> >& solu std::vector<dReal>& vFreeParameters, std::vector<std::vector<dReal> >& sol
tions, int filteroptions) const; utions, int filteroptions) const;
/** \brief returns the parameterization of a given IK type for the current manipulator position. /** \brief returns the parameterization of a given IK type for the current manipulator position.
Ideally pluging the returned ik parameterization into FindIkSol ution should return the a manipulator configuration Ideally pluging the returned ik parameterization into FindIkSol ution should return the a manipulator configuration
such that a new call to GetIkParameterization returns the same values. In other words: such that a new call to GetIkParameterization returns the same values. In other words:
\code \code
ikparam = manip->GetIkParameterization(iktype); ikparam = manip->GetIkParameterization(iktype);
... move robot ... move robot
std::vector<dReal> sol; std::vector<dReal> sol;
if( FindIKSolution(ikparam,sol, filteroptions) ) { if( FindIKSolution(ikparam,sol, filteroptions) ) {
skipping to change at line 220 skipping to change at line 207
Transform _tGrasp; Transform _tGrasp;
std::vector<dReal> _vClosingDirection; std::vector<dReal> _vClosingDirection;
Vector _vdirection; Vector _vdirection;
IkSolverBasePtr _pIkSolver; IkSolverBasePtr _pIkSolver;
std::string _strIkSolver; std::string _strIkSolver;
std::vector<std::string> _vgripperjointnames; ///< names of the gri pper joints std::vector<std::string> _vgripperjointnames; ///< names of the gri pper joints
private: private:
RobotBaseWeakPtr _probot; RobotBaseWeakPtr _probot;
std::vector<int> __vgripperdofindices, __varmdofindices; std::vector<int> __vgripperdofindices, __varmdofindices;
std::string __hashstructure, __hashkinematicsstructure; mutable std::string __hashstructure, __hashkinematicsstructure;
#ifdef RAVE_PRIVATE #ifdef RAVE_PRIVATE
#ifdef _MSC_VER #ifdef _MSC_VER
friend class ColladaReader; friend class ColladaReader;
friend class OpenRAVEXMLParser::ManipulatorXMLReader; friend class OpenRAVEXMLParser::ManipulatorXMLReader;
friend class OpenRAVEXMLParser::RobotXMLReader; friend class OpenRAVEXMLParser::RobotXMLReader;
#else #else
friend class ::ColladaReader; friend class ::ColladaReader;
friend class ::OpenRAVEXMLParser::ManipulatorXMLReader; friend class ::OpenRAVEXMLParser::ManipulatorXMLReader;
friend class ::OpenRAVEXMLParser::RobotXMLReader; friend class ::OpenRAVEXMLParser::RobotXMLReader;
#endif #endif
#endif #endif
friend class RobotBase; friend class RobotBase;
}; };
typedef boost::shared_ptr<Manipulator> ManipulatorPtr; typedef boost::shared_ptr<RobotBase::Manipulator> ManipulatorPtr;
typedef boost::shared_ptr<Manipulator const> ManipulatorConstPtr; typedef boost::shared_ptr<RobotBase::Manipulator const> ManipulatorCons
typedef boost::weak_ptr<Manipulator> ManipulatorWeakPtr; tPtr;
typedef boost::weak_ptr<RobotBase::Manipulator> ManipulatorWeakPtr;
/// \brief Attaches a sensor to a link on the robot. /// \brief Attaches a sensor to a link on the robot.
class OPENRAVE_API AttachedSensor : public boost::enable_shared_from_th is<AttachedSensor> class OPENRAVE_API AttachedSensor : public boost::enable_shared_from_th is<AttachedSensor>
{ {
public: public:
AttachedSensor(RobotBasePtr probot); AttachedSensor(RobotBasePtr probot);
AttachedSensor(RobotBasePtr probot, const AttachedSensor& sensor, i nt cloningoptions); AttachedSensor(RobotBasePtr probot, const AttachedSensor& sensor, i nt cloningoptions);
virtual ~AttachedSensor(); virtual ~AttachedSensor();
virtual SensorBasePtr GetSensor() const { return psensor; } virtual SensorBasePtr GetSensor() const { return psensor; }
skipping to change at line 270 skipping to change at line 257
/// \return hash of the sensor definition /// \return hash of the sensor definition
virtual const std::string& GetStructureHash() const; virtual const std::string& GetStructureHash() const;
private: private:
RobotBaseWeakPtr _probot; RobotBaseWeakPtr _probot;
SensorBasePtr psensor; SensorBasePtr psensor;
LinkWeakPtr pattachedlink; ///< the robot link that the sensor is a ttached to LinkWeakPtr pattachedlink; ///< the robot link that the sensor is a ttached to
Transform trelative; ///< relative transform of the sensor with res pect to the attached link Transform trelative; ///< relative transform of the sensor with res pect to the attached link
SensorBase::SensorDataPtr pdata; ///< pointer to a preallocated dat a using psensor->CreateSensorData() SensorBase::SensorDataPtr pdata; ///< pointer to a preallocated dat a using psensor->CreateSensorData()
std::string _name; ///< name of the attached sensor std::string _name; ///< name of the attached sensor
std::string __hashstructure; mutable std::string __hashstructure;
#ifdef RAVE_PRIVATE #ifdef RAVE_PRIVATE
#ifdef _MSC_VER #ifdef _MSC_VER
friend class ColladaReader; friend class ColladaReader;
friend class OpenRAVEXMLParser::AttachedSensorXMLReader; friend class OpenRAVEXMLParser::AttachedSensorXMLReader;
friend class OpenRAVEXMLParser::RobotXMLReader; friend class OpenRAVEXMLParser::RobotXMLReader;
#else #else
friend class ::ColladaReader; friend class ::ColladaReader;
friend class ::OpenRAVEXMLParser::AttachedSensorXMLReader; friend class ::OpenRAVEXMLParser::AttachedSensorXMLReader;
friend class ::OpenRAVEXMLParser::RobotXMLReader; friend class ::OpenRAVEXMLParser::RobotXMLReader;
#endif #endif
#endif #endif
friend class RobotBase; friend class RobotBase;
}; };
typedef boost::shared_ptr<AttachedSensor> AttachedSensorPtr; typedef boost::shared_ptr<RobotBase::AttachedSensor> AttachedSensorPtr;
typedef boost::shared_ptr<AttachedSensor const> AttachedSensorConstPtr; typedef boost::shared_ptr<RobotBase::AttachedSensor const> AttachedSens
orConstPtr;
/// \brief The information of a currently grabbed body. /// \brief The information of a currently grabbed body.
class OPENRAVE_API Grabbed class OPENRAVE_API Grabbed
{ {
public: public:
KinBodyWeakPtr pbody; ///< the grabbed body KinBodyWeakPtr pbody; ///< the grabbed body
LinkPtr plinkrobot; ///< robot link that is grabbing the body LinkPtr plinkrobot; ///< robot link that is grabbing the body
std::vector<LinkConstPtr> vCollidingLinks, vNonCollidingLinks; ///< robot links that already collide with the body std::vector<LinkConstPtr> vCollidingLinks, vNonCollidingLinks; ///< robot links that already collide with the body
Transform troot; ///< root transform (of first link of body) relati ve to plinkrobot's transform. In other words, pbody->GetTransform() == plin krobot->GetTransform()*troot Transform troot; ///< root transform (of first link of body) relati ve to plinkrobot's transform. In other words, pbody->GetTransform() == plin krobot->GetTransform()*troot
}; };
/// \deprecated (10/07/10)
typedef Grabbed GRABBED RAVE_DEPRECATED;
/// \brief Helper class derived from KinBodyStateSaver to additionaly s ave robot information. /// \brief Helper class derived from KinBodyStateSaver to additionaly s ave robot information.
class OPENRAVE_API RobotStateSaver : public KinBodyStateSaver class OPENRAVE_API RobotStateSaver : public KinBodyStateSaver
{ {
public: public:
RobotStateSaver(RobotBasePtr probot, int options = Save_LinkTransfo rmation|Save_LinkEnable|Save_ActiveDOF|Save_ActiveManipulator); RobotStateSaver(RobotBasePtr probot, int options = Save_LinkTransfo rmation|Save_LinkEnable|Save_ActiveDOF|Save_ActiveManipulator);
virtual ~RobotStateSaver(); virtual ~RobotStateSaver();
protected: protected:
RobotBasePtr _probot; RobotBasePtr _probot;
std::vector<int> vactivedofs; std::vector<int> vactivedofs;
int affinedofs; int affinedofs;
skipping to change at line 331 skipping to change at line 315
/// \deprecated (11/02/18) \see EnvironmentBase::ReadRobotXMLFile /// \deprecated (11/02/18) \see EnvironmentBase::ReadRobotXMLFile
virtual bool InitFromFile(const std::string& filename, const Attributes List& atts = AttributesList()) RAVE_DEPRECATED; virtual bool InitFromFile(const std::string& filename, const Attributes List& atts = AttributesList()) RAVE_DEPRECATED;
/// \deprecated (11/02/18) \see EnvironmentBase::ReadRobotXMLData /// \deprecated (11/02/18) \see EnvironmentBase::ReadRobotXMLData
virtual bool InitFromData(const std::string& data, const AttributesList & atts = AttributesList()) RAVE_DEPRECATED; virtual bool InitFromData(const std::string& data, const AttributesList & atts = AttributesList()) RAVE_DEPRECATED;
/// \brief Returns the manipulators of the robot /// \brief Returns the manipulators of the robot
virtual std::vector<ManipulatorPtr>& GetManipulators() { return _vecMan ipulators; } virtual std::vector<ManipulatorPtr>& GetManipulators() { return _vecMan ipulators; }
virtual bool SetMotion(TrajectoryBaseConstPtr ptraj) { return false; } virtual bool SetMotion(TrajectoryBaseConstPtr ptraj) { return false; }
/// \deprecated (10/07/10)
virtual std::vector<AttachedSensorPtr>& GetSensors() RAVE_DEPRECATED {
RAVELOG_WARN("RobotBase::GetSensors() is deprecated\n"); return _vecSensors
; }
virtual std::vector<AttachedSensorPtr>& GetAttachedSensors() { return _ vecSensors; } virtual std::vector<AttachedSensorPtr>& GetAttachedSensors() { return _ vecSensors; }
virtual void SetDOFValues(const std::vector<dReal>& vJointValues, bool bCheckLimits = false); virtual void SetDOFValues(const std::vector<dReal>& vJointValues, bool bCheckLimits = false);
virtual void SetDOFValues(const std::vector<dReal>& vJointValues, const Transform& transbase, bool bCheckLimits = false); virtual void SetDOFValues(const std::vector<dReal>& vJointValues, const Transform& transbase, bool bCheckLimits = false);
virtual void SetBodyTransformations(const std::vector<Transform>& vbodi es); virtual void SetLinkTransformations(const std::vector<Transform>& vbodi es);
/// Transforms the robot and updates the attached sensors and grabbed b odies. /// Transforms the robot and updates the attached sensors and grabbed b odies.
virtual void SetTransform(const Transform& trans); virtual void SetTransform(const Transform& trans);
/** Methods using the active degrees of freedoms of the robot. Active D OFs are a way for the /** Methods using the active degrees of freedoms of the robot. Active D OFs are a way for the
user to specify degrees of freedom of interest for a current execut ion block. All planners user to specify degrees of freedom of interest for a current execut ion block. All planners
by default use the robot's active DOF and active manipultor. For ev ery Get* method, there is by default use the robot's active DOF and active manipultor. For ev ery Get* method, there is
a corresponding GetActive* method rather than the methods when sett ing joints. The active a corresponding GetActive* method rather than the methods when sett ing joints. The active
DOFs also include affine transfomrations of the robot's base. Affin e transformation DOFs can DOFs also include affine transfomrations of the robot's base. Affin e transformation DOFs can
be found after the joint DOFs in this order: X, Y, Z, Rotation wher e rotation can be around be found after the joint DOFs in this order: X, Y, Z, Rotation wher e rotation can be around
skipping to change at line 389 skipping to change at line 371
\param affine A bitmask of \ref DOFAffine values \param affine A bitmask of \ref DOFAffine values
\param rotationaxis if \ref DOF_RotationAxis is specified, pRotatio nAxis is used as the new axis \param rotationaxis if \ref DOF_RotationAxis is specified, pRotatio nAxis is used as the new axis
*/ */
virtual void SetActiveDOFs(const std::vector<int>& dofindices, int affi ne, const Vector& rotationaxis); virtual void SetActiveDOFs(const std::vector<int>& dofindices, int affi ne, const Vector& rotationaxis);
virtual int GetActiveDOF() const { return _nActiveDOF >= 0 ? _nActiveDO F : GetDOF(); } virtual int GetActiveDOF() const { return _nActiveDOF >= 0 ? _nActiveDO F : GetDOF(); }
virtual int GetAffineDOF() const { return _nAffineDOFs; } virtual int GetAffineDOF() const { return _nAffineDOFs; }
/// \brief If dof is set in the affine dofs, returns its index in the d of values array, otherwise returns -1 /// \brief If dof is set in the affine dofs, returns its index in the d of values array, otherwise returns -1
virtual int GetAffineDOFIndex(DOFAffine dof) const; virtual int GetAffineDOFIndex(DOFAffine dof) const;
/// \deprecated (10/07/25)
virtual const std::vector<int>& GetActiveJointIndices() const RAVE_DEPR
ECATED { return GetActiveDOFIndices(); }
/// \brief Return the set of active dof indices of the joints. /// \brief Return the set of active dof indices of the joints.
virtual const std::vector<int>& GetActiveDOFIndices() const; virtual const std::vector<int>& GetActiveDOFIndices() const;
virtual Vector GetAffineRotationAxis() const { return vActvAffineRotati onAxis; } virtual Vector GetAffineRotationAxis() const { return vActvAffineRotati onAxis; }
virtual void SetAffineTranslationLimits(const Vector& lower, const Vect or& upper); virtual void SetAffineTranslationLimits(const Vector& lower, const Vect or& upper);
virtual void SetAffineRotationAxisLimits(const Vector& lower, const Vec tor& upper); virtual void SetAffineRotationAxisLimits(const Vector& lower, const Vec tor& upper);
virtual void SetAffineRotation3DLimits(const Vector& lower, const Vecto r& upper); virtual void SetAffineRotation3DLimits(const Vector& lower, const Vecto r& upper);
/// \brief sets the quaternion limits using a starting rotation and the max angle deviation from it. /// \brief sets the quaternion limits using a starting rotation and the max angle deviation from it.
/// ///
skipping to change at line 655 skipping to change at line 634
Vector _vTranslationLowerLimits, _vTranslationUpperLimits, _vTranslatio nMaxVels, _vTranslationResolutions, _vTranslationWeights; Vector _vTranslationLowerLimits, _vTranslationUpperLimits, _vTranslatio nMaxVels, _vTranslationResolutions, _vTranslationWeights;
/// the xyz components are used if the rotation axis is solely about X, Y,or Z; otherwise the W component is used. /// the xyz components are used if the rotation axis is solely about X, Y,or Z; otherwise the W component is used.
Vector _vRotationAxisLowerLimits, _vRotationAxisUpperLimits, _vRotation AxisMaxVels, _vRotationAxisResolutions, _vRotationAxisWeights; Vector _vRotationAxisLowerLimits, _vRotationAxisUpperLimits, _vRotation AxisMaxVels, _vRotationAxisResolutions, _vRotationAxisWeights;
Vector _vRotation3DLowerLimits, _vRotation3DUpperLimits, _vRotation3DMa xVels, _vRotation3DResolutions, _vRotation3DWeights; Vector _vRotation3DLowerLimits, _vRotation3DUpperLimits, _vRotation3DMa xVels, _vRotation3DResolutions, _vRotation3DWeights;
Vector _vRotationQuatLimitStart; Vector _vRotationQuatLimitStart;
dReal _fQuatLimitMaxAngle, _fQuatMaxAngleVelocity, _fQuatAngleResolutio n, _fQuatAngleWeight; dReal _fQuatLimitMaxAngle, _fQuatMaxAngleVelocity, _fQuatAngleResolutio n, _fQuatAngleWeight;
private: private:
virtual const char* GetHash() const { return OPENRAVE_ROBOT_HASH; } virtual const char* GetHash() const { return OPENRAVE_ROBOT_HASH; }
virtual const char* GetKinBodyHash() const { return OPENRAVE_KINBODY_HA SH; } virtual const char* GetKinBodyHash() const { return OPENRAVE_KINBODY_HA SH; }
std::string __hashrobotstructure; mutable std::string __hashrobotstructure;
mutable std::vector<dReal> _vTempRobotJoints; mutable std::vector<dReal> _vTempRobotJoints;
#ifdef RAVE_PRIVATE #ifdef RAVE_PRIVATE
#ifdef _MSC_VER #ifdef _MSC_VER
friend class Environment; friend class Environment;
friend class ColladaReader; friend class ColladaReader;
friend class ColladaWriter; friend class ColladaWriter;
friend class OpenRAVEXMLParser::RobotXMLReader; friend class OpenRAVEXMLParser::RobotXMLReader;
friend class OpenRAVEXMLParser::ManipulatorXMLReader; friend class OpenRAVEXMLParser::ManipulatorXMLReader;
friend class OpenRAVEXMLParser::AttachedSensorXMLReader; friend class OpenRAVEXMLParser::AttachedSensorXMLReader;
 End of changes. 22 change blocks. 
68 lines changed or deleted 41 lines changed or added


 sensor.h   sensor.h 
// -*- coding: utf-8 -*- // -*- coding: utf-8 -*-
// Copyright (C) 2006-2010 Rosen Diankov (rosen.diankov@gmail.com) // Copyright (C) 2006-2011 Rosen Diankov <rosen.diankov@gmail.com>
// //
// This file is part of OpenRAVE. // This file is part of OpenRAVE.
// OpenRAVE is free software: you can redistribute it and/or modify // OpenRAVE is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by // it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or // the Free Software Foundation, either version 3 of the License, or
// at your option) any later version. // at your option) any later version.
// //
// This program is distributed in the hope that it will be useful, // This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of // but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
skipping to change at line 45 skipping to change at line 45
ST_Camera=2, ST_Camera=2,
ST_JointEncoder=3, ST_JointEncoder=3,
ST_Force6D=4, ST_Force6D=4,
ST_IMU=5, ST_IMU=5,
ST_Odometry=6, ST_Odometry=6,
ST_Tactile=7, ST_Tactile=7,
ST_Actuator=8, ST_Actuator=8,
ST_NumberofSensorTypes=8 ST_NumberofSensorTypes=8
}; };
class CameraIntrinsics typedef geometry::RaveCameraIntrinsics<dReal> CameraIntrinsics;
{
public:
CameraIntrinsics() : fx(0),fy(0),cx(0),cy(0) {}
CameraIntrinsics(dReal fx, dReal fy, dReal cx, dReal cy) : fx(fx),
fy(fy), cx(cx), cy(cy) {}
dReal fx,fy, cx,cy;
};
/// used to pass sensor data around /// used to pass sensor data around
class OPENRAVE_API SensorData class OPENRAVE_API SensorData
{ {
public: public:
virtual ~SensorData() {} virtual ~SensorData() {}
virtual SensorType GetType() = 0; virtual SensorType GetType() = 0;
/// Serialize the sensor data to stream in XML format /// Serialize the sensor data to stream in XML format
virtual bool serialize(std::ostream& O) const; virtual bool serialize(std::ostream& O) const;
uint64_t __stamp; ///< time stamp of the sensor data in microsecond s. If 0, then the data is uninitialized! (floating-point precision is bad h ere). This can be either simulation or real time depending on the sensor. uint64_t __stamp; ///< time stamp of the sensor data in microsecond s. If 0, then the data is uninitialized! (floating-point precision is bad h ere). This can be either simulation or real time depending on the sensor.
Transform __trans; ///< the coordinate system the sensor was wh en the measurement was taken, this is taken directly from SensorBase::GetTr ansform
}; };
typedef boost::shared_ptr<SensorData> SensorDataPtr; typedef boost::shared_ptr<SensorBase::SensorData> SensorDataPtr;
typedef boost::shared_ptr<SensorData const> SensorDataConstPtr; typedef boost::shared_ptr<SensorBase::SensorData const> SensorDataConst
Ptr;
class OPENRAVE_API LaserSensorData : public SensorData class OPENRAVE_API LaserSensorData : public SensorData
{ {
public: public:
virtual SensorType GetType() { return ST_Laser; } virtual SensorType GetType() { return ST_Laser; }
Transform t; ///< the coordinate system all the measurements ar e in
std::vector<RaveVector<dReal> > positions; ///< world coordinates o f the origins of each of the laser points. std::vector<RaveVector<dReal> > positions; ///< world coordinates o f the origins of each of the laser points.
///< if positions is empty, assume t he origin is t.trans for all points ///< if positions is empty, assume t he origin is t.trans for all points
std::vector<RaveVector<dReal> > ranges; ///< Range and direction re adings in the form of direction*distance. The direction is in world coordin ates. The values should be returned in the order laser detected them in. std::vector<RaveVector<dReal> > ranges; ///< Range and direction re adings in the form of direction*distance. The direction is in world coordin ates. The values should be returned in the order laser detected them in.
std::vector<dReal> intensity; ///< Intensity readings. std::vector<dReal> intensity; ///< Intensity readings.
virtual bool serialize(std::ostream& O) const; virtual bool serialize(std::ostream& O) const;
}; };
class OPENRAVE_API CameraSensorData : public SensorData class OPENRAVE_API CameraSensorData : public SensorData
{ {
public: public:
virtual SensorType GetType() { return ST_Camera; } virtual SensorType GetType() { return ST_Camera; }
Transform t; ///< the coordinate system all the measurements we re taken in
std::vector<uint8_t> vimagedata; ///< rgb image data, if camera onl y outputs in grayscale, fill each channel with the same value std::vector<uint8_t> vimagedata; ///< rgb image data, if camera onl y outputs in grayscale, fill each channel with the same value
virtual bool serialize(std::ostream& O) const; virtual bool serialize(std::ostream& O) const;
}; };
/// \brief Stores joint angles and EE position. /// \brief Stores joint angles and EE position.
class OPENRAVE_API JointEncoderSensorData : public SensorData class OPENRAVE_API JointEncoderSensorData : public SensorData
{ {
public: public:
virtual SensorType GetType() { return ST_JointEncoder; } virtual SensorType GetType() { return ST_JointEncoder; }
std::vector<dReal> encoderValues; ///< measured joint angles in rad ians std::vector<dReal> encoderValues; ///< measured joint angles in rad ians
skipping to change at line 170 skipping to change at line 163
dReal appliedcurrent; ///< current sent to the actuator dReal appliedcurrent; ///< current sent to the actuator
}; };
/// permanent properties of the sensors /// permanent properties of the sensors
class OPENRAVE_API SensorGeometry class OPENRAVE_API SensorGeometry
{ {
public: public:
virtual ~SensorGeometry() {} virtual ~SensorGeometry() {}
virtual SensorType GetType() = 0; virtual SensorType GetType() = 0;
}; };
typedef boost::shared_ptr<SensorGeometry> SensorGeometryPtr; typedef boost::shared_ptr<SensorBase::SensorGeometry> SensorGeometryPtr
typedef boost::shared_ptr<SensorGeometry const> SensorGeometryConstPtr; ;
typedef boost::shared_ptr<SensorBase::SensorGeometry const> SensorGeome
tryConstPtr;
class OPENRAVE_API LaserGeomData : public SensorGeometry class OPENRAVE_API LaserGeomData : public SensorGeometry
{ {
public: public:
LaserGeomData() : min_range(0), max_range(0), time_increment(0), time_s can(0) { min_angle[0] = min_angle[1] = max_angle[0] = max_angle[1] = resolu tion[0] = resolution[1] = 0; } LaserGeomData() : min_range(0), max_range(0), time_increment(0), time_s can(0) { min_angle[0] = min_angle[1] = max_angle[0] = max_angle[1] = resolu tion[0] = resolution[1] = 0; }
virtual SensorType GetType() { return ST_Laser; } virtual SensorType GetType() { return ST_Laser; }
boost::array<dReal,2> min_angle; ///< Start for the laser scan [rad ]. boost::array<dReal,2> min_angle; ///< Start for the laser scan [rad ].
boost::array<dReal,2> max_angle; ///< End angles for the laser scan [rad]. boost::array<dReal,2> max_angle; ///< End angles for the laser scan [rad].
boost::array<dReal,2> resolution; ///< Angular resolutions for each axis of rotation [rad]. boost::array<dReal,2> resolution; ///< Angular resolutions for each axis of rotation [rad].
dReal min_range, max_range; ///< Maximum range [m]. dReal min_range, max_range; ///< Maximum range [m].
skipping to change at line 281 skipping to change at line 274
/// \brief Configures properties of the sensor like power. /// \brief Configures properties of the sensor like power.
/// ///
/// \param type \ref ConfigureCommand /// \param type \ref ConfigureCommand
/// \param blocking If set to true, makes sure the configuration ends b efore this function returns.(might cause problems if environment is locked) . /// \param blocking If set to true, makes sure the configuration ends b efore this function returns.(might cause problems if environment is locked) .
/// \throw openrave_exception if command doesn't succeed /// \throw openrave_exception if command doesn't succeed
virtual int Configure(ConfigureCommand command, bool blocking=false) = 0; virtual int Configure(ConfigureCommand command, bool blocking=false) = 0;
/// \brief Simulate one step forward for sensors. /// \brief Simulate one step forward for sensors.
/// ///
/// Only valid if this sensor is simulation based. A sensor hooked up t o a real device can ignore this call /// Only valid if this sensor is simulation based. A sensor hooked up t o a real device can ignore this call
virtual bool SimulationStep(dReal fTimeElapsed) { throw openrave_except ion("SensorBase::SimulationStep not implemented",ORE_NotImplemented); } virtual bool SimulationStep(dReal fTimeElapsed) OPENRAVE_DUMMY_IMPLEMEN TATION;
/// \brief Returns the sensor geometry. This method is thread safe. /// \brief Returns the sensor geometry. This method is thread safe.
/// ///
/// \param type the requested sensor type to create. A sensor can suppo rt many types. If type is ST_Invalid, then returns a data structure /// \param type the requested sensor type to create. A sensor can suppo rt many types. If type is ST_Invalid, then returns a data structure
/// \return sensor geometry pointer, use delete to destroy it /// \return sensor geometry pointer, use delete to destroy it
virtual SensorGeometryPtr GetSensorGeometry(SensorType type=ST_Invalid) = 0; virtual SensorGeometryPtr GetSensorGeometry(SensorType type=ST_Invalid) = 0;
/// \brief Creates the sensor data to be specifically used by this clas s /// \brief Creates the sensor data to be specifically used by this clas s
/// \param type the requested sensor type to create. A sensor can suppo rt many types. If type is ST_Invalid, then returns a data structure /// \param type the requested sensor type to create. A sensor can suppo rt many types. If type is ST_Invalid, then returns a data structure
/// of the type most representative of this sensor. /// of the type most representative of this sensor.
skipping to change at line 315 skipping to change at line 308
/// \brief Set the transform of a sensor (global coordinate system). /// \brief Set the transform of a sensor (global coordinate system).
/// ///
/// Sensors attached to the robot have their transforms automatically s et every time the robot is moved /// Sensors attached to the robot have their transforms automatically s et every time the robot is moved
/// \param trans - The transform defining the frame of the sensor. /// \param trans - The transform defining the frame of the sensor.
virtual void SetTransform(const Transform& trans) = 0; virtual void SetTransform(const Transform& trans) = 0;
virtual Transform GetTransform() = 0; virtual Transform GetTransform() = 0;
/// \brief Register a callback whenever new sensor data comes in. /// \brief Register a callback whenever new sensor data comes in.
/// \param type the sensor type to register for /// \param type the sensor type to register for
/// \param callback the user function to call, note that this might blo ck the thread generating/receiving sensor data /// \param callback the user function to call, note that this might blo ck the thread generating/receiving sensor data
virtual boost::shared_ptr<void> RegisterDataCallback(SensorType type, c onst boost::function<void(SensorDataConstPtr)>& callback) { throw openrave_ exception("SensorBase::RegisterDataCallback",ORE_NotImplemented); } virtual boost::shared_ptr<void> RegisterDataCallback(SensorType type, c onst boost::function<void(SensorDataConstPtr)>& callback) OPENRAVE_DUMMY_IM PLEMENTATION;
/// \return the name of the sensor /// \return the name of the sensor
virtual const std::string& GetName() const { return _name; } virtual const std::string& GetName() const { return _name; }
virtual void SetName(const std::string& newname) { _name = newname; } virtual void SetName(const std::string& newname) { _name = newname; }
/// \deprecated (11/03/28) /// \deprecated (11/03/28)
virtual bool Init(const std::string&) RAVE_DEPRECATED { RAVELOG_WARN("S ensorBase::Init has been deprecated\n"); return Configure(CC_PowerOn)>0; } virtual bool Init(const std::string&) RAVE_DEPRECATED { RAVELOG_WARN("S ensorBase::Init has been deprecated\n"); return Configure(CC_PowerOn)>0; }
virtual void Reset(int) RAVE_DEPRECATED { RAVELOG_WARN("SensorBase::Res et has been deprecated\n"); Configure(CC_PowerOff); } virtual void Reset(int) RAVE_DEPRECATED { RAVELOG_WARN("SensorBase::Res et has been deprecated\n"); Configure(CC_PowerOff); }
protected: protected:
 End of changes. 9 change blocks. 
17 lines changed or deleted 12 lines changed or added


 trajectory.h   trajectory.h 
skipping to change at line 128 skipping to change at line 128
/// return the static interface type this class points to (used for saf e casting) /// return the static interface type this class points to (used for saf e casting)
static inline InterfaceType GetInterfaceTypeStatic() { return PT_Trajec tory; } static inline InterfaceType GetInterfaceTypeStatic() { return PT_Trajec tory; }
/// clears all points and resets the dof of the trajectory /// clears all points and resets the dof of the trajectory
virtual void Reset(int nDOF); virtual void Reset(int nDOF);
/// getting information about the trajectory /// getting information about the trajectory
inline dReal GetTotalDuration() const { return _vecpoints.size() > 0 ? _vecpoints.back().time : 0; } inline dReal GetTotalDuration() const { return _vecpoints.size() > 0 ? _vecpoints.back().time : 0; }
InterpEnum GetInterpMethod() const { return _interpMethod; } InterpEnum GetInterpMethod() const { return _interpMethod; }
const std::vector<TPOINT>& GetPoints() const { return _vecpoints; } const std::vector<TrajectoryBase::TPOINT>& GetPoints() const { return _
std::vector<TPOINT>& GetPoints() { return _vecpoints; } vecpoints; }
const std::vector<TSEGMENT>& GetSegments() const { return _vecsegments; std::vector<TrajectoryBase::TPOINT>& GetPoints() { return _vecpoints; }
} const std::vector<TrajectoryBase::TSEGMENT>& GetSegments() const { retu
rn _vecsegments; }
virtual void Clear(); virtual void Clear();
/// add a point to the trajectory /// add a point to the trajectory
virtual void AddPoint(const TPOINT& p) { assert( _nDOF == (int)p.q.size ()); _vecpoints.push_back(p); } virtual void AddPoint(const TrajectoryBase::TPOINT& p) { assert( _nDOF == (int)p.q.size()); _vecpoints.push_back(p); }
/** \brief Preprocesses the trajectory for later sampling and set its i nterpolation method. /** \brief Preprocesses the trajectory for later sampling and set its i nterpolation method.
\param[in] robot [optional] robot to do the timing for \param[in] robot [optional] robot to do the timing for
\param[in] interpolationMethod method to use for interpolation \param[in] interpolationMethod method to use for interpolation
\param bAutoCalcTiming If true, will retime the trajectory using ma ximum joint velocities and accelerations, otherwise it expects the time sta mps of each point to be set. \param bAutoCalcTiming If true, will retime the trajectory using ma ximum joint velocities and accelerations, otherwise it expects the time sta mps of each point to be set.
\param[in] bActiveDOFs If true, then the trajectory is specified in the robot's active degrees of freedom \param[in] bActiveDOFs If true, then the trajectory is specified in the robot's active degrees of freedom
and the maximum velocities and accelerations will be extracted appr opriately. Affine transformations and the maximum velocities and accelerations will be extracted appr opriately. Affine transformations
are ignored in the retiming if true. If false, then use the are ignored in the retiming if true. If false, then use the
robot's full joint configuration and affine transformation for max velocities. robot's full joint configuration and affine transformation for max velocities.
\param[in] fMaxVelMult The percentage of the max velocity of each j oint to use when retiming. \param[in] fMaxVelMult The percentage of the max velocity of each j oint to use when retiming.
*/ */
virtual bool CalcTrajTiming(RobotBaseConstPtr robot, InterpEnum interpo lationMethod, bool bAutoCalcTiming, bool bActiveDOFs, dReal fMaxVelMult=1); virtual bool CalcTrajTiming(RobotBaseConstPtr robot, InterpEnum interpo lationMethod, bool bAutoCalcTiming, bool bActiveDOFs, dReal fMaxVelMult=1);
/// perform basic error checking on the trajectory internal data. /// \deprecated (11/06/14) see planningutils::ValidateTrajectory
/// virtual bool IsValid() const RAVE_DEPRECATED;
/// checks internal data structures and verifies that all trajectory
/// via points do not violate joint position, velocity, and
/// acceleration limits.
virtual bool IsValid() const;
/// tests if a point violates any position, velocity or accel constrain ts /// tests if a point violates any position, velocity or accel constrain ts
//virtual bool IsValidPoint(const TPOINT& tp) const; //virtual bool IsValidPoint(const TPOINT& tp) const;
/// \brief Sample the trajectory at the given time using the current in terpolation method. /// \brief Sample the trajectory at the given time using the current in terpolation method.
virtual bool SampleTrajectory(dReal time, TPOINT &sample) const; virtual bool SampleTrajectory(dReal time, TrajectoryBase::TPOINT &samp le) const;
/// Write to a stream, see TrajectoryOptions for file format /// Write to a stream, see TrajectoryOptions for file format
/// \param sinput stream to read the data from /// \param sinput stream to read the data from
/// \param options a combination of enums in TrajectoryOptions /// \param options a combination of enums in TrajectoryOptions
virtual bool Write(std::ostream& sinput, int options) const; virtual bool Write(std::ostream& sinput, int options) const;
/// Reads the trajectory, expects the filename to have a header. /// Reads the trajectory, expects the filename to have a header.
/// \param sout stream to output the trajectory data /// \param sout stream to output the trajectory data
/// \param robot The robot to attach the trajrectory to, if specified, will /// \param robot The robot to attach the trajrectory to, if specified, will
/// call CalcTrajTiming to get the correct trajectory velo cities. /// call CalcTrajTiming to get the correct trajectory velo cities.
skipping to change at line 194 skipping to change at line 191
/// calculate the coefficients of a the parabolic and linear blends /// calculate the coefficients of a the parabolic and linear blends
/// with continuous endpoint positions and velocities for via points. /// with continuous endpoint positions and velocities for via points.
//virtual void _CalculateLinearBlendCoefficients(TSEGMENT::Type segType ,TSEGMENT& seg, TSEGMENT& prev,TPOINT& p0, TPOINT& p1,const dReal blendAcce l[]); //virtual void _CalculateLinearBlendCoefficients(TSEGMENT::Type segType ,TSEGMENT& seg, TSEGMENT& prev,TPOINT& p0, TPOINT& p1,const dReal blendAcce l[]);
/// cubic spline interpolation /// cubic spline interpolation
virtual bool _SetCubic(bool bAutoCalcTiming, bool bActiveDOFs); virtual bool _SetCubic(bool bAutoCalcTiming, bool bActiveDOFs);
/// calculate the coefficients of a smooth cubic spline with /// calculate the coefficients of a smooth cubic spline with
/// continuous endpoint positions and velocities for via points. /// continuous endpoint positions and velocities for via points.
virtual void _CalculateCubicCoefficients(TSEGMENT& , const TPOINT& tp0, const TPOINT& tp1); virtual void _CalculateCubicCoefficients(TrajectoryBase::TSEGMENT& , co nst TrajectoryBase::TPOINT& tp0, const TrajectoryBase::TPOINT& tp1);
//bool _SetQuintic(bool bAutoCalcTiming, bool bActiveDOFs); //bool _SetQuintic(bool bAutoCalcTiming, bool bActiveDOFs);
/// calculate the coefficients of a smooth quintic spline with /// calculate the coefficients of a smooth quintic spline with
/// continuous endpoint positions and velocities for via points /// continuous endpoint positions and velocities for via points
/// using minimum jerk heuristics /// using minimum jerk heuristics
//void _CalculateQuinticCoefficients(TSEGMENT&, TPOINT& tp0, TPOINT& tp 1); //void _CalculateQuinticCoefficients(TSEGMENT&, TPOINT& tp0, TPOINT& tp 1);
/// recalculate all via point velocities and accelerations /// recalculate all via point velocities and accelerations
virtual void _RecalculateViaPointDerivatives(); virtual void _RecalculateViaPointDerivatives();
/// computes minimum time interval for linear interpolation between /// computes minimum time interval for linear interpolation between
/// path points that does not exceed the maximum joint velocities /// path points that does not exceed the maximum joint velocities
virtual dReal _MinimumTimeLinear(const TPOINT& p0, const TPOINT& p1, bo ol bActiveDOFs); virtual dReal _MinimumTimeLinear(const TrajectoryBase::TPOINT& p0, cons t TrajectoryBase::TPOINT& p1, bool bActiveDOFs);
/// computes minimum time interval for cubic interpolation between /// computes minimum time interval for cubic interpolation between
/// path points that does not exceed the maximum joint velocities /// path points that does not exceed the maximum joint velocities
/// or accelerations /// or accelerations
virtual dReal _MinimumTimeCubic(const TPOINT& p0, const TPOINT& p1, boo l bActiveDOFs); virtual dReal _MinimumTimeCubic(const TrajectoryBase::TPOINT& p0, const TrajectoryBase::TPOINT& p1, bool bActiveDOFs);
/// computes minimum time interval for cubic interpolation between /// computes minimum time interval for cubic interpolation between
/// path points that does not exceed the maximum joint velocities /// path points that does not exceed the maximum joint velocities
/// or accelerations assuming zero velocities at endpoints /// or accelerations assuming zero velocities at endpoints
virtual dReal _MinimumTimeCubicZero(const TPOINT& p0, const TPOINT& p1, bool bActiveDOFs); virtual dReal _MinimumTimeCubicZero(const TrajectoryBase::TPOINT& p0, c onst TrajectoryBase::TPOINT& p1, bool bActiveDOFs);
/// computes minimum time interval for quintic interpolation between /// computes minimum time interval for quintic interpolation between
/// path points that does not exceed the maximum joint velocities /// path points that does not exceed the maximum joint velocities
/// or accelerations /// or accelerations
virtual dReal _MinimumTimeQuintic(const TPOINT& p0, const TPOINT& p1, b ool bActiveDOFs); virtual dReal _MinimumTimeQuintic(const TrajectoryBase::TPOINT& p0, con st TrajectoryBase::TPOINT& p1, bool bActiveDOFs);
virtual dReal _MinimumTimeTransform(const Transform& t0, const Transfor m& t1); virtual dReal _MinimumTimeTransform(const Transform& t0, const Transfor m& t1);
/// find the active trajectory interval covering the given time /// find the active trajectory interval covering the given time
/// (returns the index of the start point of the interval) /// (returns the index of the start point of the interval)
virtual int _FindActiveInterval(dReal time) const; virtual int _FindActiveInterval(dReal time) const;
/// \brief Sample the trajectory using linear interpolation. /// \brief Sample the trajectory using linear interpolation.
virtual bool _SampleLinear(const TPOINT& p0, const TPOINT& p1, const TS EGMENT& seg, dReal time, TPOINT& sample) const; virtual bool _SampleLinear(const TrajectoryBase::TPOINT& p0, const Traj ectoryBase::TPOINT& p1, const TrajectoryBase::TSEGMENT& seg, dReal time, Tr ajectoryBase::TPOINT& sample) const;
/// \brief Sample using linear interpolation with parabolic blends. /// \brief Sample using linear interpolation with parabolic blends.
virtual bool _SampleLinearBlend(const TPOINT& p0, const TPOINT& p1, con st TSEGMENT& seg, dReal time, TPOINT& sample) const; virtual bool _SampleLinearBlend(const TrajectoryBase::TPOINT& p0, const TrajectoryBase::TPOINT& p1, const TrajectoryBase::TSEGMENT& seg, dReal tim e, TrajectoryBase::TPOINT& sample) const;
/// \brief Sample the trajectory using cubic interpolation. /// \brief Sample the trajectory using cubic interpolation.
virtual bool _SampleCubic(const TPOINT& p0, const TPOINT& p1, const TSE GMENT& seg, dReal time, TPOINT& sample) const; virtual bool _SampleCubic(const TrajectoryBase::TPOINT& p0, const Traje ctoryBase::TPOINT& p1, const TrajectoryBase::TSEGMENT& seg, dReal time, Tra jectoryBase::TPOINT& sample) const;
/// \brief Sample the trajectory using quintic interpolation with minim um jerk. /// \brief Sample the trajectory using quintic interpolation with minim um jerk.
virtual bool _SampleQuintic(const TPOINT& p0, const TPOINT& p1, const T SEGMENT& seg, dReal time, TPOINT& sample) const; virtual bool _SampleQuintic(const TrajectoryBase::TPOINT& p0, const Tra jectoryBase::TPOINT& p1, const TrajectoryBase::TSEGMENT& seg, dReal time, T rajectoryBase::TPOINT& sample) const;
std::vector<TPOINT> _vecpoints; std::vector<TrajectoryBase::TPOINT> _vecpoints;
std::vector<TSEGMENT> _vecsegments; std::vector<TSEGMENT> _vecsegments;
std::vector<dReal> _lowerJointLimit, _upperJointLimit, _maxJointVel, _m axJointAccel; std::vector<dReal> _lowerJointLimit, _upperJointLimit, _maxJointVel, _m axJointAccel;
Vector _maxAffineTranslationVel; Vector _maxAffineTranslationVel;
dReal _maxAffineRotationQuatVel; dReal _maxAffineRotationQuatVel;
int _nQuaternionIndex; ///< the index of a quaternion rotation, if one exists (interpolation is different for quaternions) int _nQuaternionIndex; ///< the index of a quaternion rotation, if one exists (interpolation is different for quaternions)
/// computes the difference of two states necessary for correct interpo lation when there are circular joints. Default is regular subtraction. /// computes the difference of two states necessary for correct interpo lation when there are circular joints. Default is regular subtraction.
/// _diffstatefn(q1,q2) -> q1 -= q2 /// _diffstatefn(q1,q2) -> q1 -= q2
boost::function<void(std::vector<dReal>&,const std::vector<dReal>&)> _d iffstatefn; boost::function<void(std::vector<dReal>&,const std::vector<dReal>&)> _d iffstatefn;
 End of changes. 14 change blocks. 
22 lines changed or deleted 20 lines changed or added


 viewer.h   viewer.h 
skipping to change at line 37 skipping to change at line 37
/// Designed to be multi-thread safe and destruction and modification of th e viewer plot can be done at any time. The viewers /// Designed to be multi-thread safe and destruction and modification of th e viewer plot can be done at any time. The viewers
/// internally handle synchronization and threading issues. /// internally handle synchronization and threading issues.
class OPENRAVE_API GraphHandle class OPENRAVE_API GraphHandle
{ {
public: public:
virtual ~GraphHandle() {} virtual ~GraphHandle() {}
/// \brief Changes the underlying transformation of the plot. <b>[multi -thread safe]</b> /// \brief Changes the underlying transformation of the plot. <b>[multi -thread safe]</b>
/// ///
/// \param t new transformation of the plot /// \param t new transformation of the plot
virtual void SetTransform(const RaveTransform<float>& t) { throw openra ve_exception("GraphHandle::SetTransform not implemented",ORE_NotImplemented ); } virtual void SetTransform(const RaveTransform<float>& t) OPENRAVE_DUMMY _IMPLEMENTATION;
/// \brief Shows or hides the plot without destroying its resources. <b >[multi-thread safe]</b> /// \brief Shows or hides the plot without destroying its resources. <b >[multi-thread safe]</b>
virtual void SetShow(bool bshow) { throw openrave_exception("GraphHandl e::SetShow not implemented",ORE_NotImplemented); } virtual void SetShow(bool bshow) OPENRAVE_DUMMY_IMPLEMENTATION;
}; };
typedef boost::shared_ptr<GraphHandle> GraphHandlePtr; typedef boost::shared_ptr<GraphHandle> GraphHandlePtr;
typedef boost::shared_ptr<GraphHandle const> GraphHandleConstPtr; typedef boost::shared_ptr<GraphHandle const> GraphHandleConstPtr;
typedef boost::weak_ptr<GraphHandle const> GraphHandleWeakPtr; typedef boost::weak_ptr<GraphHandle const> GraphHandleWeakPtr;
/** \brief <b>[interface]</b> Base class for the graphics and gui engine th at renders the environment and provides visual sensor information. /** \brief <b>[interface]</b> Base class for the graphics and gui engine th at renders the environment and provides visual sensor information. See \ref arch_viewer.
\ingroup interfaces \ingroup interfaces
*/ */
class OPENRAVE_API ViewerBase : public InterfaceBase class OPENRAVE_API ViewerBase : public InterfaceBase
{ {
public: public:
enum ViewerEvents enum ViewerEvents
{ {
/// mouse button is clicked. If the function
/// returns true, then the object will be selected. Otherwise, the
object remains unselected.
VE_ItemSelection = 1, VE_ItemSelection = 1,
}; } RAVE_DEPRECATED;
ViewerBase(EnvironmentBasePtr penv) : InterfaceBase(PT_Viewer, penv) {} ViewerBase(EnvironmentBasePtr penv) : InterfaceBase(PT_Viewer, penv) {}
virtual ~ViewerBase() {} virtual ~ViewerBase() {}
/// return the static interface type this class points to (used for saf e casting) /// \brief return the static interface type this class points to (used for safe casting)
static inline InterfaceType GetInterfaceTypeStatic() { return PT_Viewer ; } static inline InterfaceType GetInterfaceTypeStatic() { return PT_Viewer ; }
/// \brief goes into the main loop /// \brief goes into the main loop
///
/// \param bShow if true will show the window /// \param bShow if true will show the window
virtual int main(bool bShow = true) = 0; virtual int main(bool bShow = true) = 0;
/// destroys the main loop
/// \brief destroys the main loop
virtual void quitmainloop() = 0; virtual void quitmainloop() = 0;
//@{ GUI interaction methods //@{ GUI interaction methods
/// \brief Set the camera transformation. /// \brief Set the camera transformation.
/// ///
/// \param trans new camera transformation in the world coordinate syst em /// \param trans new camera transformation in the world coordinate syst em
/// \param focalDistance The new focal distance of the camera (higher v alues is higher zoom). If 0, then the previous focal distance is preserved. /// \param focalDistance The new focal distance of the camera (higher v alues is higher zoom). If 0, then the previous focal distance is preserved.
virtual void SetCamera(const RaveTransform<float>& trans, float focalDi stance=0) { throw openrave_exception("ViewerBase::SetCamera not implemented ",ORE_NotImplemented); } virtual void SetCamera(const RaveTransform<float>& trans, float focalDi stance=0) OPENRAVE_DUMMY_IMPLEMENTATION;
/// \brief Return the current camera transform that the viewer is rende ring the environment at. /// \brief Return the current camera transform that the viewer is rende ring the environment at.
virtual RaveTransform<float> GetCameraTransform() { throw openrave_exce ption("ViewerBase::GetCameraTransform not implemented",ORE_NotImplemented); } virtual RaveTransform<float> GetCameraTransform() const OPENRAVE_DUMMY_ IMPLEMENTATION;
/// \brief reset the camera depending on its mode /// \brief Return the closest camera intrinsics that the viewer is rend
virtual void UpdateCameraTransform() { throw openrave_exception("Viewer ering the environment at.
Base::UpdateCameraTransform not implemented",ORE_NotImplemented); } virtual geometry::RaveCameraIntrinsics<float> GetCameraIntrinsics() con
st OPENRAVE_DUMMY_IMPLEMENTATION;
/// Renders a 24bit RGB image of dimensions width and height from the c /** \brief Renders a 24bit RGB image of dimensions width and height fro
urrent scene. The camera m the current scene.
/// is meant to show the underlying OpenRAVE world as a robot would see
it, so all graphs The camera is meant to show the underlying OpenRAVE world as a robo
/// rendered with the plotX and drawX functions are hidden. t would see it, so all graphs
/// \param memory the memory where the image will be stored at, has to rendered with the plotX and drawX functions are hidden by default.
store 3*width*height Some viewers support the SetFiguresInCamera command to allow graphs to be a
/// \param width width of the image lso displayed.
/// \param height height of the image \param memory the memory where the image will be stored at, has to
/// \param t the rotation and translation of the camera. Note that z is store 3*width*height
treated as the front of the camera! \param width width of the image, if 0 the width of the viewer is us
/// So all points in front of the camera have a positive dot pro ed
duct with its direction. \param height height of the image, if 0 the width of the viewer is
/// \param KK 4 values such that the intrinsic matrix can be reconstruc used
ted [pKK[0] 0 pKK[2]; 0 pKK[1] pKK[3]; 0 0 1]; \param t the rotation and translation of the camera. Note that +z i
virtual bool GetCameraImage(std::vector<uint8_t>& memory, int width, in s treated as the camera direction axis! So all points in front of the camer
t height, const RaveTransform<float>& t, const SensorBase::CameraIntrinsics a have a positive dot product with its +z direction.
& KK) { throw openrave_exception("ViewerBase::GetCameraImage not implemente \param intrinsics the intrinsic parameters of the camera defining F
d",ORE_NotImplemented); } OV, distortion, principal point, and focal length. The focal length is used
to define the near plane for culling.
*/
virtual bool GetCameraImage(std::vector<uint8_t>& memory, int width, in
t height, const RaveTransform<float>& t, const SensorBase::CameraIntrinsics
& intrinsics) OPENRAVE_DUMMY_IMPLEMENTATION;
//@} //@}
virtual void Reset() { throw openrave_exception("ViewerBase::Reset not virtual void Reset() OPENRAVE_DUMMY_IMPLEMENTATION;
implemented",ORE_NotImplemented); } virtual void SetBkgndColor(const RaveVector<float>& color) OPENRAVE_DUM
virtual void SetBkgndColor(const RaveVector<float>& color) { throw open MY_IMPLEMENTATION;
rave_exception("ViewerBase::SetBkgndColor not implemented",ORE_NotImplement
ed); }
/// callback viewer function when for viewer events /// \brief callback function for item selection
/// first parameter - target openrave link ///
/// second parameter - offset /// If the function returns true, then the object will be selected. Oth
/// third parameter - direction erwise, the object remains unselected.
typedef boost::function<bool(KinBody::LinkPtr plink,RaveVector<float>,R /// callback(target link,offset,direction)
aveVector<float>)> ViewerCallbackFn; typedef boost::function<bool(KinBody::LinkPtr plink,RaveVector<float>,R
aveVector<float>)> ItemSelectionCallbackFn;
/// \brief registers a function with the viewer that gets called everyt /// \brief registers a function with the viewer that gets called everyt
ime a specified event occurs (part of ViewerEvents enum) ime mouse button is clicked
/// \return a handle to the callback. If this handle is deleted, the ca ///
llback will be unregistered /// \return a handle to the callback. If this handle is deleted, the ca
virtual boost::shared_ptr<void> RegisterCallback(int properties, const llback will be unregistered.
ViewerCallbackFn& fncallback) { throw openrave_exception("ViewerBase::Regis virtual boost::shared_ptr<void> RegisterItemSelectionCallback(const Ite
terCallback not implemented",ORE_NotImplemented); } mSelectionCallbackFn& fncallback) OPENRAVE_DUMMY_IMPLEMENTATION;
/// \brief controls whether the viewer synchronizes with the newest env /// \brief callback function for item selection
ironment /// callback(imagememory,width,height,pixeldepth)
virtual void SetEnvironmentSync(bool bUpdate) { throw openrave_exceptio ///
n("ViewerBase::SetEnvironmentSync not implemented",ORE_NotImplemented); } /// \param imagememory width x height x pixeldepth RGB image
typedef boost::function<void(const uint8_t*,int,int,int)> ViewerImageCa
llbackFn;
/// \brief registers a function with the viewer that gets called for ev
ery new image rendered.
///
/// \return a handle to the callback. If this handle is deleted, the ca
llback will be unregistered.
virtual boost::shared_ptr<void> RegisterViewerImageCallback(const Viewe
rImageCallbackFn& fncallback) OPENRAVE_DUMMY_IMPLEMENTATION;
/// \brief controls whether the viewer synchronizes with the newest env
ironment automatically
virtual void SetEnvironmentSync(bool bUpdate) OPENRAVE_DUMMY_IMPLEMENTA
TION;
/// \brief forces synchronization with the environment, returns when th e environment is fully synchronized. /// \brief forces synchronization with the environment, returns when th e environment is fully synchronized.
/// ///
/// Note that this method might not work if environment is locked in cu rrent thread /// Note that this method might not work if environment is locked in cu rrent thread
virtual void EnvironmentSync() { throw openrave_exception("ViewerBase:: EnvironmentSync not implemented",ORE_NotImplemented); } virtual void EnvironmentSync() OPENRAVE_DUMMY_IMPLEMENTATION;
virtual void ViewerSetSize(int w, int h) { throw openrave_exception("Vi virtual void SetSize(int w, int h) OPENRAVE_DUMMY_IMPLEMENTATION;
ewerBase::ViewerSetSize not implemented",ORE_NotImplemented); }
virtual void ViewerMove(int x, int y) { throw openrave_exception("Viewe /// \deprecated (11/06/13)
rBase::ViewerMove not implemented",ORE_NotImplemented); } virtual void ViewerSetSize(int w, int h) RAVE_DEPRECATED { SetSize(w,h)
virtual void ViewerSetTitle(const std::string& ptitle) { throw openrave ; }
_exception("ViewerBase::ViewerSetTitle not implemented",ORE_NotImplemented)
; } virtual void Move(int x, int y) OPENRAVE_DUMMY_IMPLEMENTATION;
/// \deprecated (11/06/13)
virtual void ViewerMove(int x, int y) RAVE_DEPRECATED { Move(x,y); };
virtual void SetName(const std::string& name) OPENRAVE_DUMMY_IMPLEMENTA
TION;
/// \deprecated (11/06/13)
virtual void ViewerSetTitle(const std::string& ptitle) RAVE_DEPRECATED
{ SetName(ptitle); }
virtual const std::string& GetName() const OPENRAVE_DUMMY_IMPLEMENTATIO
N;
/// \deprecated (11/06/10)
virtual void UpdateCameraTransform() RAVE_DEPRECATED OPENRAVE_DUMMY_IMP
LEMENTATION;
/// \deprecated (11/06/10)
typedef ItemSelectionCallbackFn ViewerCallbackFn RAVE_DEPRECATED;
/// \deprecated (11/06/10)
virtual boost::shared_ptr<void> RegisterCallback(int properties, const
ViewerCallbackFn& fncallback) RAVE_DEPRECATED
{
return RegisterItemSelectionCallback(fncallback);
}
/// \deprecated (11/03/02) Any type of model should be added through th e openrave environment instead of viewer directly. /// \deprecated (11/03/02) Any type of model should be added through th e openrave environment instead of viewer directly.
virtual bool LoadModel(const std::string& pfilename) { throw openrave_e xception("ViewerBase::LoadModel not implemented",ORE_NotImplemented); } virtual bool LoadModel(const std::string& pfilename) RAVE_DEPRECATED OP ENRAVE_DUMMY_IMPLEMENTATION;
protected: protected:
virtual GraphHandlePtr plot3(const float* ppoints, int numPoints, int s virtual GraphHandlePtr plot3(const float* ppoints, int numPoints, int s
tride, float fPointSize, const RaveVector<float>& color, int drawstyle = 0) tride, float fPointSize, const RaveVector<float>& color, int drawstyle = 0)
{ throw openrave_exception("ViewerBase::plot3 not implemented",ORE_NotImpl OPENRAVE_DUMMY_IMPLEMENTATION;
emented); } virtual GraphHandlePtr plot3(const float* ppoints, int numPoints, int s
virtual GraphHandlePtr plot3(const float* ppoints, int numPoints, int s tride, float fPointSize, const float* colors, int drawstyle = 0, bool bhasa
tride, float fPointSize, const float* colors, int drawstyle = 0, bool bhasa lpha=false) OPENRAVE_DUMMY_IMPLEMENTATION;
lpha=false) { throw openrave_exception("ViewerBase::plot3 not implemented",
ORE_NotImplemented); }
virtual GraphHandlePtr drawlinestrip(const float* ppoints, int numPoint virtual GraphHandlePtr drawlinestrip(const float* ppoints, int numPoint
s, int stride, float fwidth, const RaveVector<float>& color) { throw openra s, int stride, float fwidth, const RaveVector<float>& color) OPENRAVE_DUMMY
ve_exception("ViewerBase::drawlinestrip not implemented",ORE_NotImplemented _IMPLEMENTATION;
); } virtual GraphHandlePtr drawlinestrip(const float* ppoints, int numPoint
virtual GraphHandlePtr drawlinestrip(const float* ppoints, int numPoint s, int stride, float fwidth, const float* colors) OPENRAVE_DUMMY_IMPLEMENTA
s, int stride, float fwidth, const float* colors) { throw openrave_exceptio TION;
n("ViewerBase::drawlinestrip not implemented",ORE_NotImplemented); }
virtual GraphHandlePtr drawlinelist(const float* ppoints, int numPoints virtual GraphHandlePtr drawlinelist(const float* ppoints, int numPoints
, int stride, float fwidth, const RaveVector<float>& color) { throw openrav , int stride, float fwidth, const RaveVector<float>& color) OPENRAVE_DUMMY_
e_exception("ViewerBase::drawlinelist not implemented",ORE_NotImplemented); IMPLEMENTATION;
} virtual GraphHandlePtr drawlinelist(const float* ppoints, int numPoints
virtual GraphHandlePtr drawlinelist(const float* ppoints, int numPoints , int stride, float fwidth, const float* colors) OPENRAVE_DUMMY_IMPLEMENTAT
, int stride, float fwidth, const float* colors) { throw openrave_exception ION;
("ViewerBase::drawlinelist not implemented",ORE_NotImplemented); }
virtual GraphHandlePtr drawarrow(const RaveVector<float>& p1, const Rav eVector<float>& p2, float fwidth, const RaveVector<float>& color) { throw o penrave_exception("ViewerBase::drawarrow not implemented",ORE_NotImplemente d); } virtual GraphHandlePtr drawarrow(const RaveVector<float>& p1, const Rav eVector<float>& p2, float fwidth, const RaveVector<float>& color) OPENRAVE_ DUMMY_IMPLEMENTATION;
virtual GraphHandlePtr drawbox(const RaveVector<float>& vpos, const Rav virtual GraphHandlePtr drawbox(const RaveVector<float>& vpos, const Rav
eVector<float>& vextents) { throw openrave_exception("ViewerBase::drawbox n eVector<float>& vextents) OPENRAVE_DUMMY_IMPLEMENTATION;
ot implemented",ORE_NotImplemented); } virtual GraphHandlePtr drawplane(const RaveTransform<float>& tplane, co
virtual GraphHandlePtr drawplane(const RaveTransform<float>& tplane, co nst RaveVector<float>& vextents, const boost::multi_array<float,3>& vtextur
nst RaveVector<float>& vextents, const boost::multi_array<float,3>& vtextur e) OPENRAVE_DUMMY_IMPLEMENTATION;
e) { throw openrave_exception("ViewerBase::drawplane not implemented",ORE_N
otImplemented); }
virtual GraphHandlePtr drawtrimesh(const float* ppoints, int stride, co virtual GraphHandlePtr drawtrimesh(const float* ppoints, int stride, co
nst int* pIndices, int numTriangles, const RaveVector<float>& color) { thro nst int* pIndices, int numTriangles, const RaveVector<float>& color) OPENRA
w openrave_exception("ViewerBase::drawtrimesh not implemented",ORE_NotImple VE_DUMMY_IMPLEMENTATION;
mented); } virtual GraphHandlePtr drawtrimesh(const float* ppoints, int stride, co
virtual GraphHandlePtr drawtrimesh(const float* ppoints, int stride, co nst int* pIndices, int numTriangles, const boost::multi_array<float,2>& col
nst int* pIndices, int numTriangles, const boost::multi_array<float,2>& col ors) OPENRAVE_DUMMY_IMPLEMENTATION;
ors) { throw openrave_exception("ViewerBase::drawtrimesh not implemented",O
RE_NotImplemented); } inline ViewerBasePtr shared_viewer() { return boost::static_pointer_cas
t<ViewerBase>(shared_from_this()); }
inline ViewerBaseConstPtr shared_viewer_const() const { return boost::s
tatic_pointer_cast<ViewerBase const>(shared_from_this()); }
private: private:
virtual const char* GetHash() const { return OPENRAVE_VIEWER_HASH; } virtual const char* GetHash() const { return OPENRAVE_VIEWER_HASH; }
#ifdef RAVE_PRIVATE #ifdef RAVE_PRIVATE
#ifdef _MSC_VER #ifdef _MSC_VER
friend class Environment; friend class Environment;
#else #else
friend class ::Environment; friend class ::Environment;
#endif #endif
#endif #endif
}; };
typedef ViewerBase RaveViewerBase RAVE_DEPRECATED;
typedef ViewerBasePtr RaveViewerBasePtr RAVE_DEPRECATED;
typedef ViewerBaseConstPtr RaveViewerBaseConstPtr RAVE_DEPRECATED;
typedef ViewerBaseWeakPtr RaveViewerBaseWeakPtr RAVE_DEPRECATED;
} // end namespace OpenRAVE } // end namespace OpenRAVE
#endif #endif
 End of changes. 26 change blocks. 
107 lines changed or deleted 143 lines changed or added

This html diff was produced by rfcdiff 1.41. The latest version is available from http://tools.ietf.org/tools/rfcdiff/