31 #ifndef HPP_PINOCCHIO_JOINT_HH
32 #define HPP_PINOCCHIO_JOINT_HH
37 #include <hpp/util/serialization-fwd.hh>
83 const std::string&
name()
const;
92 return currentTransformation(data());
179 if (maximalDistanceToParent_ < 0) computeMaximalDistanceToParent();
180 return maximalDistanceToParent_;
200 return jacobian(data(), localFrame);
211 const bool localFrame =
true)
const;
230 std::ostream&
display(std::ostream& os)
const;
248 return (joint ? joint->index() : 0);
256 return index() == other.
index() && robot() == other.
robot();
Robot with geometric and dynamic pinocchio.
Definition: device.hh:60
JointJacobian_t & jacobian(DeviceData &data, const bool localFrame=true) const
void isBounded(size_type rank, bool bounded)
value_type maximalDistanceToParent_
Definition: joint.hh:262
static JointPtr_t create(DeviceWkPtr_t device, JointIndex indexInJointList)
JointPtr_t childJoint(std::size_t rank) const
Get child joint.
const Transform3s & positionInParentFrame() const
std::ostream & display(std::ostream &os) const
Display joint.
void upperBound(size_type rank, value_type upperBound)
Set upper bound of given degree of freedom.
const value_type & maximalDistanceToParent()
Maximal distance of joint origin to parent origin.
Definition: joint.hh:178
value_type upperBound(size_type rank) const
Get upper bound of given degree of freedom.
DeviceData & data() const
DevicePtr_t robot()
Access robot owning the object.
Definition: joint.hh:219
const Model & model() const
value_type lowerBound(size_type rank) const
Get lower bound of given degree of freedom.
size_type numberDof() const
Return number of degrees of freedom.
BodyPtr_t linkedBody() const
Get linked body.
void computeMaximalDistanceToParent()
Compute the maximal distance.
std::vector< JointIndex > children
Definition: joint.hh:265
static size_type index(const JointConstPtr_t &joint)
Definition: joint.hh:247
Joint()
Definition: joint.hh:278
JointPtr_t parentJoint() const
Get a pointer to the parent joint (if any).
void lowerBound(size_type rank, value_type lowerBound)
Set lower bound of given degree of freedom.
~Joint()
Definition: joint.hh:76
std::size_t numberChildJoints() const
Number of child joints.
size_type rankInVelocity() const
Return rank of the joint in the velocity vector.
void lowerBounds(vectorIn_t lowerBounds)
Set lower bounds.
const std::string & name() const
Get name.
DeviceConstPtr_t robot() const
Access robot owning the object.
Definition: joint.hh:217
size_type rankInConfiguration() const
Return rank of the joint in the configuration vector.
value_type upperBoundLinearVelocity() const
const Transform3s & currentTransformation(const DeviceData &data) const
Joint transformation.
void selfAssert() const
Assert that the members of the struct are valid (no null pointer, etc).
LiegroupSpacePtr_t RnxSOnConfigurationSpace() const
Joint(DeviceWkPtr_t device, JointIndex indexInJointList)
bool operator==(const Joint &other) const
Definition: joint.hh:255
bool operator!=(const Joint &other) const
Definition: joint.hh:259
void setChildList()
Store list of childrens.
value_type upperBoundAngularVelocity() const
const JointIndex & index() const
Definition: joint.hh:242
void upperBounds(vectorIn_t upperBounds)
Set upper bounds.
const Transform3s & currentTransformation() const
Joint transformation.
Definition: joint.hh:91
DeviceWkPtr_t devicePtr
Definition: joint.hh:263
size_type configSize() const
Return number of degrees of freedom.
JointIndex jointIndex
Definition: joint.hh:264
const JointModel & jointModel() const
JointJacobian_t & jacobian(const bool localFrame=true) const
Definition: joint.hh:199
bool isBounded(size_type rank) const
Get whether given degree of freedom is bounded.
LiegroupSpacePtr_t configurationSpace() const
Get configuration space of joint.
#define HPP_PINOCCHIO_DLLAPI
Definition: config.hh:88
shared_ptr< Device > DevicePtr_t
Definition: fwd.hh:118
shared_ptr< Joint > JointPtr_t
Definition: fwd.hh:123
::pinocchio::ModelTpl< value_type, 0, JointCollectionTpl > Model
Definition: fwd.hh:77
std::ostream & operator<<(std::ostream &os, const hpp::pinocchio::Device &device)
Definition: device.hh:366
shared_ptr< LiegroupSpace > LiegroupSpacePtr_t
Definition: fwd.hh:150
matrix_t::Index size_type
Definition: fwd.hh:97
Eigen::Matrix< value_type, 6, Eigen::Dynamic > JointJacobian_t
Definition: fwd.hh:101
::pinocchio::JointModelTpl< value_type, 0, JointCollectionTpl > JointModel
Definition: fwd.hh:84
shared_ptr< Body > BodyPtr_t
Definition: fwd.hh:109
::pinocchio::SE3 Transform3s
Definition: fwd.hh:81
double value_type
Definition: fwd.hh:51
::pinocchio::JointIndex JointIndex
Definition: fwd.hh:74
shared_ptr< const Joint > JointConstPtr_t
Definition: fwd.hh:124
shared_ptr< const Device > DeviceConstPtr_t
Definition: fwd.hh:119
Eigen::Ref< const vector_t > vectorIn_t
Definition: fwd.hh:93
Utility functions.
Definition: body.hh:39
Definition: collision-object.hh:40
Definition: device-data.hh:51