Template Class UrdfVisitor

Inheritance Relationships

Base Type

Derived Type

Class Documentation

template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
class UrdfVisitor : public pinocchio::urdf::details::UrdfVisitorBaseTpl<Scalar, Options>

Subclassed by pinocchio::urdf::details::UrdfVisitorWithRootJoint< Scalar, Options, JointCollectionTpl >

Public Types

typedef UrdfVisitorBaseTpl<Scalar, Options> Base
typedef Base::JointType JointType
typedef Base::Vector3 Vector3
typedef Base::VectorConstRef VectorConstRef
typedef Base::SE3 SE3
typedef Base::Inertia Inertia
typedef ModelTpl<Scalar, Options, JointCollectionTpl> Model
typedef Model::JointCollection JointCollection
typedef Model::JointModel JointModel
typedef Model::Frame Frame

Public Functions

inline UrdfVisitor(Model &model)
inline UrdfVisitor(Model &model, const std::string &rjn)
inline virtual void setName(const std::string &name)
inline virtual void addRootJoint(const Inertia &Y, const std::string &body_name)
inline virtual void addJointAndBody(JointType type, const Vector3 &axis, const FrameIndex &parentFrameId, const SE3 &placement, const std::string &joint_name, const Inertia &Y, const std::string &body_name, const VectorConstRef &max_effort, const VectorConstRef &max_velocity, const VectorConstRef &min_config, const VectorConstRef &max_config, const VectorConstRef &friction, const VectorConstRef &damping)
inline virtual void addJointAndBody(JointType type, const Vector3 &axis, const FrameIndex &parentFrameId, const SE3 &placement, const std::string &joint_name, const Inertia &Y, const SE3 &frame_placement, const std::string &body_name, const VectorConstRef &max_effort, const VectorConstRef &max_velocity, const VectorConstRef &min_config, const VectorConstRef &max_config, const VectorConstRef &friction, const VectorConstRef &damping)
inline virtual void addFixedJointAndBody(const FrameIndex &parent_frame_id, const SE3 &joint_placement, const std::string &joint_name, const Inertia &Y, const std::string &body_name)
inline virtual void appendBodyToJoint(const FrameIndex fid, const Inertia &Y, const SE3 &placement, const std::string &body_name)
inline virtual FrameIndex getBodyId(const std::string &frame_name) const
inline virtual FrameIndex getJointId(const std::string &joint_name) const
inline virtual const std::string &getJointName(const JointIndex jointId) const
inline virtual Frame getBodyFrame(const std::string &frame_name) const
inline virtual JointIndex getParentId(const std::string &frame_name) const
inline virtual bool existFrame(const std::string &frame_name, const FrameType type) const
template<typename TypeX, typename TypeY, typename TypeZ, typename TypeUnaligned>
inline JointIndex addJoint(const Vector3 &axis, const Frame &frame, const SE3 &placement, const std::string &joint_name, const VectorConstRef &max_effort, const VectorConstRef &max_velocity, const VectorConstRef &min_config, const VectorConstRef &max_config, const VectorConstRef &friction, const VectorConstRef &damping)

Public Members

Model &model
std::string root_joint_name