127 root->get_joint_value(values);
175 root->get_joint_vel(vels);
193 vels(
i_dof+1) = rd(1);
194 vels(
i_dof+2) = rd(2);
199 vels(
i_dof+1) = pd(1);
200 vels(
i_dof+2) = pd(2);
201 vels(
i_dof+3) = rd(0);
202 vels(
i_dof+4) = rd(1);
203 vels(
i_dof+5) = rd(2);
217 root->get_joint_acc(accs);
223 static fVec3 pdd, rdd;
234 accs(
i_dof) = rdd(0);
235 accs(
i_dof+1) = rdd(1);
236 accs(
i_dof+2) = rdd(2);
240 accs(
i_dof) = pdd(0);
241 accs(
i_dof+1) = pdd(1);
242 accs(
i_dof+2) = pdd(2);
243 accs(
i_dof+3) = rdd(0);
244 accs(
i_dof+4) = rdd(1);
245 accs(
i_dof+5) = rdd(2);
398 if(!jnt->
parent)
return -1;
401 static fVec3 pp, r_pos;
403 pp.
sub(abs_pos, p_pos);
406 r_att.
mul(tR, abs_att);
417 if(values.
size() != n_value)
419 cerr <<
"Chain::SetJointValue: error - size of the argument should be n_value (" << n_value <<
")" << endl;
422 root->set_joint_value(values);
460 cerr <<
"Chain::SetJointVel: error - size of the argument should be n_dof (" <<
n_dof <<
")" << endl;
463 root->set_joint_vel(vels);
501 cerr <<
"Chain::SetJointAcc: error - size of the argument should be n_dof (" <<
n_dof <<
")" << endl;
504 root->set_joint_acc(accs);
550 static fVec3 tmp, tmp1;
750 cerr <<
"Chain::SetJointForce: error - size of the argument should be n_dof (" <<
n_dof <<
")" << endl;
753 root->set_joint_force(forces);
870 cerr <<
"Chain::GetJointForce: error - size of the argument should be n_dof (" <<
n_dof <<
")" << endl;
873 root->get_joint_force(forces);
914 root->clear_joint_force();
930 root->clear_ext_force();
void add(const fVec3 &vec1, const fVec3 &vec2)
int ClearJointForce()
Clear the joint forces/torques.
fVec3 axis
joint axis in local frame (for 1DOF joints)
int SetJointPosition(const fVec3 &p)
Set relative position.
Joint * child
pointer to the child joint
int SetJointValue(const fVec &values)
Set all joint values.
int n_dof
degrees of freedom (0/1/3/6)
void zero()
Creates a zero vector.
int set_joint_vel(const fVec &vels)
int t_given
torque or motion controlled
void set(const fMat33 &mat)
Copies a matrix.
void mul(const fMat33 &mat1, const fMat33 &mat2)
int n_thrust
DOF for motion controlled joints.
friend fMat33 tran(const fMat33 &m)
Returns the transpose.
fVec3 init_pos
origin of the joint value (for prismatic joints)
void SetFixedJointType(const fVec3 &rpos, const fMat33 &ratt)
Set joint type to fixed.
int SetJointAcc(const fVec &accs)
void set(double *v)
Set element values from array or three values.
int GetJointVel(fVec &vels)
int SetJointVel(const fVec &vels)
Set all joint velocities/accelerations.
fEulerPara rel_ep
Euler parameter representation of rel_att (for 0/3/6 DOF joints)
void set(const fVec3 &v, double s)
Set the elements.
int SetJointAcc(double _qdd)
double q
joint value (for 1DOF joints)
double tau
joint force/torque (for 1DOF joints)
double TotalMass()
Returns the total mass of the child links.
int GetJointAcc(fVec &accs)
void rot2mat(const fVec3 &, double)
Converts from/to equivalent rotation axis and angle.
fVec3 rel_pos
(initial) position in parent joint's frame (for 0/3/6 DOF joints)
int set_joint_force(const fVec &forces)
int GetJointValue(double &_q)
int i_dof
index in all DOF
int SetJointForce(double _tau)
int get_joint_acc(fVec &accs)
double qd
joint velocity (for 1DOF joints)
fVec3 tau_n
joint torque for 3 and 6 DOF joints
JointType j_type
joint type
fVec3 ext_force
external force
fMat33 abs_att
absolute orientation
int get_joint_force(fVec &forces)
void SetSlideJointType(const fVec3 &rpos, const fMat33 &ratt, AxisIndex ai)
Set joint type to prismatic.
fVec3 tau_f
joint force for 6DOF joints
void SetSphereJointType(const fVec3 &rpos, const fMat33 &ratt)
Set joint type to spherical.
void resize(int i)
Change the size.
fMat33 init_att
origin of the joint value (for rotational joints)
Joint * brother
pointer to the brother joint
int set_joint_acc(const fVec &accs)
Classes for defining open/closed kinematic chains.
int GetJointForce(fVec &forces)
Obtain the joint forces/torques.
int get_joint_value(fVec &values)
void SetRotateJointType(const fVec3 &rpos, const fMat33 &ratt, AxisIndex ai)
Set joint type to rotational.
fMat33 rel_att
(initial) orientation in parent joint's frame (for 0/3/6 DOF joints)
int SetJointOrientation(const fMat33 &r)
Set relative orientation.
int GetJointAcc(double &_qdd)
int SetJointForce(const fVec &forces)
Set all joint forces/torques.
void sub(const fVec3 &vec1, const fVec3 &vec2)
int SetJointValue(double _q)
int GetJointForce(double &_tau)
int GetJointValue(fVec &values)
Obtain the joint values/velocities/accelerations.
double qdd
joint acceleration (for 1DOF joints)
AxisIndex
Direction of a 1-DOF joint.
fVec3 ext_moment
external moment around the local frame
int set_joint_value(const fVec &values)
fVec3 abs_pos
absolute position
void mul(const fVec3 &vec, double d)
int ClearExtForce()
Clear the external forces/torques.
The class for representing a joint.
int get_joint_vel(fVec &vels)
int set_abs_position_orientation(Joint *jnt, const fVec3 &abs_pos, const fMat33 &abs_att)
int GetJointVel(double &_qd)
int SetJointVel(double _qd)
Joint * parent
pointer to the parent joint
int size() const
Size of the vector (same as row()).
int i_value
index in all joint values
void SetFreeJointType(const fVec3 &rpos, const fMat33 &ratt)
Set joint type to free.