23 #include <SceneGraph.h> 31 #define DEFAULT_MIN_TIMESTEP 1e-6 32 #define DEFAULT_MAX_INTEG_ERROR 1e-4 77 double _mass,
const fMat33& _inertia,
const fVec3& _com,
78 int _t_given =
true) {
83 name =
new char [strlen(_name) + 1];
164 Joint* FindJoint(
const char* jname,
const char* charname = 0);
167 Joint* FindJoint(
int _id);
170 Joint* FindCharacterRoot(
const char* charname);
178 int BeginCreateChain(
int append =
false);
195 int AddRoot(
Joint* r);
204 int Load(
const char* fname,
const char* charname = 0);
207 int LoadXML(
const char* fname,
const char* charname = 0);
225 int AddJoint(
Joint* target,
const char*
parent_name,
const char* charname = 0);
244 int CreateSerial(
int num_joint,
const JointData& joint_data,
const char* charname = 0,
Joint* parent_joint = 0);
257 int CreateParallel(
int num_char,
const char* prmname,
const char* charname,
259 const fVec3& pos_offset = 0.0,
const fMat33& att_offset = 1.0,
263 int RemoveJoint(
Joint*
j);
271 int EndCreateChain();
273 int EndCreateChain(SceneGraph* sg = NULL);
281 int GetJointNameList(
char**& jnames);
288 int GetJointList(
Joint**& joints);
314 int ClearJointForce();
330 void CalcAcceleration();
340 virtual void Clear();
362 double TotalCOM(
fVec3&
com,
const char* chname = 0);
372 double ComJacobian(
fMat& J,
fVec3& com,
const char* chname = 0);
375 int Integrate(
double timestep);
394 int IntegrateRK4(
double timestep,
int step);
401 int IntegrateValue(
double timestep);
402 int IntegrateVelocity(
double timestep);
403 int IntegrateRK4Value(
double timestep,
int step);
404 int IntegrateRK4Velocity(
double timestep,
int step);
407 int Save(
const char* fname,
const char* charname = 0)
const;
408 int Save(ostream& ost,
const char* charname = 0)
const;
411 int SaveXML(
const char* fname,
const char* charname = 0)
const;
412 int SaveXML(ostream& ost,
const char* charname = 0)
const;
418 int SetStatus(
const fVec& value,
const fVec& vel,
const fVec& acc);
421 int Connect(
Joint* virtual_joint,
Joint* parent_joint);
423 int Disconnect(
Joint* j);
426 int SetTorqueGiven(
Joint* _joint,
int _tg);
428 int SetAllTorqueGiven(
int _tg);
430 int SetCharacterTorqueGiven(
const char* charname,
int _tg);
440 virtual int init(SceneGraph* sg);
441 void set_relative_positions(SceneGraph* sg);
442 void calc_abs_positions(
Joint* cur, SceneGraph* sg);
443 void calc_rel_positions(
Joint* cur, SceneGraph* sg);
460 double* j_value_dot[4];
478 void set_all_torque_given(
Joint* cur,
int _tg);
498 joint_name = std::string(_joint_name);
502 joint_name.append(sep);
503 joint_name.append(std::string(_char_name));
513 void clear_scale_object_list();
515 void ApplyGeomScale(SceneGraph* sg);
519 void init_scale(SceneGraph* sg);
520 virtual void apply_scale();
523 void init_scale_sub(Node* node);
525 void apply_scale_top(
Joint* top,
double scale);
526 void apply_scale_sub(
Joint* cur,
double scale);
527 void reset_scale_sub(
Joint* jnt);
529 void _apply_scale(
Joint* jnt,
double scale);
530 void apply_geom_scale(SceneGraph* sg,
Joint* cur);
550 void SetJointData(
JointData* jdata,
const char* charname);
551 void UpdateJointType();
594 int SetJointAcc(
double lx,
double ly,
double lz,
double ax,
double ay,
double az);
602 int SetJointPosition(
const fVec3& p);
605 int SetJointOrientation(
const fMat33& r);
612 void SetSphereJointType(
const fVec3& rpos,
const fMat33& ratt);
614 void SetFixedJointType(
const fVec3& rpos,
const fMat33& ratt);
616 void SetFreeJointType(
const fVec3& rpos,
const fMat33& ratt);
619 int CalcJacobian(
fMat& J);
622 int CalcJacobian2(
fMat* J2);
625 int CalcJdot(
fVec& jdot);
631 int DescendantNumJoints();
634 int isDescendant(
Joint* target);
637 int isAscendant(
Joint* target);
650 if(ret)
return ret+1;
655 void SetName(
const char* _name,
const char* _charname = 0) {
664 name =
new char [strlen(_name) + strlen(_charname) + 2];
669 name =
new char [strlen(_name) + 1];
776 void _init_virtual();
781 int post_integrate();
785 int set_joint_value(
const fVec& values);
786 int set_joint_vel(
const fVec& vels);
787 int set_joint_acc(
const fVec& accs);
788 int set_joint_force(
const fVec& forces);
790 int get_joint_value(
fVec& values);
791 int get_joint_vel(
fVec& vels);
792 int get_joint_acc(
fVec& accs);
793 int get_joint_force(
fVec& forces);
795 void calc_position();
796 void calc_velocity();
797 void calc_acceleration();
802 void calc_joint_force(
fVec& tau);
804 void get_joint_name_list(
char** jnames);
805 void get_joint_list(
Joint** joints);
807 void add_child(
Joint* j);
808 int remove_child(
Joint* j);
809 Joint* find_joint(
const char*
n,
const char* charname);
810 Joint* find_joint(
int _id);
812 int calc_jacobian(
fMat& J,
Joint* target);
813 int calc_jacobian_rotate(
fMat& J,
Joint* target);
814 int calc_jacobian_slide(
fMat& J,
Joint* target);
815 int calc_jacobian_sphere(
fMat& J,
Joint* target);
816 int calc_jacobian_free(
fMat& J,
Joint* target);
818 int calc_jacobian_2(
fMat* J,
Joint* target);
819 int calc_jacobian_2_rotate_sub(
fMat* J,
Joint* target,
Joint* j1);
821 int calc_jacobian_2_sphere_sub(
fMat* J,
Joint* target,
Joint* j1);
824 int calc_jacobian_2_rotate_rotate(
fMat* J,
Joint* target,
Joint* j1,
const fVec3& axis1,
int index1,
const fVec3& axis2,
int index2);
825 int calc_jacobian_2_slide_rotate(
fMat* J,
Joint* target,
Joint* jk,
const fVec3& k_axis,
int k_index,
const fVec3& loc_axis,
int loc_index);
826 int calc_jacobian_2_rotate_slide(
fMat* J,
Joint* target,
Joint* jk,
const fVec3& k_axis,
int k_index,
const fVec3& loc_axis,
int loc_index);
829 int descendant_dof();
830 int descendant_num_joints();
833 int save(ostream& ost,
int indent,
const char* charname)
const;
834 int save_xml(ostream& ost,
int indent,
const char* charname)
const;
836 int clear_joint_force();
837 int clear_ext_force();
839 double total_com(
fVec3&
com,
const char* chname);
840 double com_jacobian(
fMat& J,
fVec3&
com,
const char* chname);
std::list< scale_object > scale_object_list
char * realname
name of the real joint (for closed chains)
fVec3 loc_lin_vel
linear velocity in local frame
scale_object(const scale_object &ref)
virtual int init(SceneGraph *sg)
Initialize the parameters.
fVec3 axis
joint axis in local frame (for 1DOF joints)
Joint * child
pointer to the child joint
#define DEFAULT_MIN_TIMESTEP
Defines for IntegAdaptiveEuler.
fVec3 loc_com_acc
com acceleration in local frame
int SetJointValue(const fVec &values)
Set all joint values.
int n_dof
degrees of freedom (0/1/3/6)
void clear(CorbaSequence &seq)
JointType j_type
joint type
void SetName(const char *_name, const char *_charname=0)
Change the joint name.
void zero()
Creates a zero vector.
int t_given
torque or motion controlled
void set(const fMat33 &mat)
Copies a matrix.
int n_thrust
DOF for motion controlled joints.
int in_create_chain
true if between BeginCreateChain() and EndCreateChain().
#define DEFAULT_MAX_INTEG_ERROR
fVec3 rpos_real
relative position in the real joint frame
fMat33 rel_att
initial orientation in parent joint's frame
fVec3 loc_ang_vel
angular velocity in local frame
fVec3 loc_lin_acc
linear acceleration in local frame
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
fVec3 init_pos
origin of the joint value (for prismatic joints)
Joint * root
Chain information.
char * parent_name
parent joint's name
int SetJointAcc(const fVec &accs)
Euler parameter representation of orientation.
fVec3 com
link center of mass in local frame
void identity()
Identity matrix.
void set(double *v)
Set element values from array or three values.
fVec3 loc_com_vel
com velocity in local frame
static char charname_separator
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)
char * basename
joint base name (without the character name)
int n_thrust
total DOF of the joints with t_given = false
int SetJointAcc(double _qdd)
double q
joint value (for 1DOF joints)
double tau
joint force/torque (for 1DOF joints)
int GetJointAcc(fVec &accs)
std::string basename(const std::string name)
int i_thrust
index in all motion controlled joints
int NumValue()
Dimension of the joint value vector (using Euler parameter representation for orientation).
fVec3 rel_pos
(initial) position in parent joint's frame (for 0/3/6 DOF joints)
int GetJointValue(double &_q)
int n_root_dof
total DOF in the root side
int i_dof
index in all DOF
int SetJointForce(double _tau)
double Scale()
Returns the scale applied to the joint.
double ** all_value
Pointers to the integration variables.
double qd
joint velocity (for 1DOF joints)
fVec3 tau_n
joint torque for 3 and 6 DOF joints
def j(str, encoding="cp932")
JointType j_type
joint type
int NumDOF()
Total degrees of freedom.
fVec3 ext_force
external force
fMat33 abs_att
absolute orientation
char * CharName() const
Returns the character name.
int do_connect
true after Connect() was called; application (or subclass) must reset the flag
char * name
joint name (including the character name)
char * CharName(const char *_name)
Extracts the character name from a joint name.
fMat33 inertia
link inertia
fVec3 tau_f
joint force for 6DOF joints
fMat33 init_att
origin of the joint value (for rotational joints)
Joint * brother
pointer to the brother joint
void append(SDOPackage::NVList &dest, const SDOPackage::NVList &src)
fVec3 loc_com
center of mass in local frame
JointData(const char *_name, const char *_parent_name, JointType _j_type, const fVec3 &_rpos, const fMat33 &_ratt, AxisIndex _axis_index, double _mass, const fMat33 &_inertia, const fVec3 &_com, int _t_given=true)
3x3 matrix and 3-element vector classes.
int GetJointForce(fVec &forces)
Obtain the joint forces/torques.
fMat33 ratt_real
relative orientation in the real joint frame
fMat33 rel_att
(initial) orientation in parent joint's frame (for 0/3/6 DOF joints)
int GetJointAcc(double &_qdd)
The class representing the whole mechanism. May contain multiple characters.
int SetJointForce(const fVec &forces)
Set all joint forces/torques.
std::string sprintf(char const *__restrict fmt,...)
Temporary storage for basic joint information.
int SetJointValue(double _q)
int GetJointForce(double &_tau)
int GetJointValue(fVec &values)
Obtain the joint values/velocities/accelerations.
virtual int clear_data()
Clear arrays only; don't delete joints.
void set_joint_name(const char *_joint_name, const char *_char_name)
int NumJoint()
Total number of joints.
double qdd
joint acceleration (for 1DOF joints)
JointType
Enums for joint types.
AxisIndex
Direction of a 1-DOF joint.
fVec3 ext_moment
external moment around the local frame
fVec3 abs_pos
absolute position
The class for representing a joint.
Joint * real
pointer to the real (connected) joint; for closed chains.
int i_joint
index of the joint
fVec3 rel_pos
initial position in parent joint's frame
int GetJointVel(double &_qd)
int SetJointVel(double _qd)
Joint * parent
pointer to the parent joint
fVec3 loc_ang_acc
angular acceleration in local frame
int i_value
index in all joint values
JointData(const JointData &ref)
int t_given
if true, the joint is torque controlled, otherwise position controlled (high-gain control) ...
Matrix of generic size. The elements are stored in a one-dimensional array in row-major order...
AxisIndex axis_index
direction of the joint axis (only for 1DOF joints)