33 bool World::LinkPairKey::operator<(
const LinkPairKey& pair2)
const 35 if((body1 == pair2.body1 && body2 == pair2.body2) ||
36 (body2 == pair2.body1 && body1 == pair2.body2 )){
38 if(pair2.link1 < pair2.link2){
39 return (link1 < pair2.link1) ?
true : (link2 < pair2.link2);
41 return (link1 < pair2.link2) ?
true : (link2 < pair2.link1);
44 if(pair2.link1 < pair2.link2){
45 return (link2 < pair2.link1) ?
true : (link1 < pair2.link2);
47 return (link2 < pair2.link2) ?
true : (link1 < pair2.link1);
52 if(pair2.body1 < pair2.body2){
53 return (body1 < pair2.body1) ?
true : (body2 < pair2.body2);
55 return (body1 < pair2.body2) ?
true : (body2 < pair2.body1);
58 if(pair2.body1 < pair2.body2){
59 return (body2 < pair2.body1) ?
true : (body1 < pair2.body2);
61 return (body2 < pair2.body2) ?
true : (body1 < pair2.body1);
85 for(
int i=0;
i<n_sensors;
i++)
91 for(
int i=0;
i<n_pairs;
i++)
134 pForwardDynamics->setEulerMethod();
136 pForwardDynamics->setRungeKuttaMethod();
138 pForwardDynamics->setGravityAcceleration(
g);
139 pForwardDynamics->setTimeStep(
timeStep_);
141 pForwardDynamics->initialize();
149 cout <<
"World current time = " <<
currentTime_ << endl;
154 for(
int i=0;
i<n_pair;
i++)
157 OpenHRP::Collision& col = corbaCollisionSequence[
i];
158 int n_point = col.points.length();
159 if(n_point == 0)
continue;
162 for(
int j=0;
j<n_point;
j++)
164 OpenHRP::CollisionPoint& point = col.points[
j];
166 pos0(0) = point.position[0];
167 pos0(1) = point.position[1];
168 pos0(2) = point.position[2];
169 norm0(0) = point.normal[0];
170 norm0(1) = point.normal[1];
171 norm0(2) = point.normal[2];
209 logfile <<
"update sensors ->" << endl;
212 for(
int i=0;
i<
n;
i++)
233 logfile <<
"<- update sensors" << endl;
239 logfile <<
"force sensor: " << fs->name << endl;
243 logfile <<
"localR = " << fs->localR << endl;
244 logfile <<
"localPos = " << fs->localPos << endl;
245 fVec3 local_f, local_n,
n;
249 local_n.
mul(n, fs->localR);
268 as->
dv.
mul(acc_j, as->localR);
284 std::pair<int,bool> World::getIndexOfLinkPairs(
BodyPtr body1, Link* link1,
BodyPtr body2, Link* link2)
287 int isRegistered =
false;
291 LinkPairKey linkPair;
292 linkPair.body1 = body1;
293 linkPair.link1 = link1;
294 linkPair.body2 = body2;
295 linkPair.link2 = link2;
297 LinkPairKeyToIndexMap::iterator p = linkPairKeyToIndexMap.find(linkPair);
299 if(p != linkPairKeyToIndexMap.end()){
304 linkPairKeyToIndexMap[linkPair] = index;
308 return std::make_pair(index, isRegistered);
314 Sensor* sensor = Sensor::create(sensorType);
315 sensor->joint = _joint;
317 sensor->name = _name;
318 sensor->localPos.
set(_localPos);
319 sensor->localR.
set(_localR);
327 int n_sensors =
sensors.size();
328 for(
int i=0;
i<n_sensors;
i++)
331 !strcmp(
sensors[
i]->joint->CharName(), charName))
342 int n_sensors =
sensors.size();
343 for(
int i=0;
i<n_sensors;
i++)
346 (!charName || !strcmp(
sensors[
i]->joint->CharName(), charName)))
357 for(
int i=0;
i<nchar;
i++)
365 if(index < 0)
return;
368 rdata->length(n_joints);
369 for(
int i=0;
i<n_links;
i++)
384 (*rdata)[index] = cur->
q;
388 (*rdata)[index] = cur->
qd;
392 (*rdata)[index] = cur->
qdd;
396 (*rdata)[index] = cur->
tau;
409 for(
int i=0;
i<nchar;
i++)
417 if(index < 0)
return;
419 int n_links = cinfo.
links.size();
420 for(
int i=0;
i<n_links;
i++)
431 if(index < (
int)wdata.length() &&
461 a[offset++] = vec(0);
462 a[offset++] = vec(1);
468 a[0] = mat(0,0); a[1] = mat(0,1); a[2] = mat(0,2);
469 a[3] = mat(1,0); a[4] = mat(1,1); a[5] = mat(1,2);
470 a[6] = mat(2,0); a[7] = mat(2,1); a[8] = mat(2,2);
476 for(
int i=0;
i<nchar;
i++)
479 OpenHRP::CharacterPosition& char_pos = all_char_pos[
i];
480 int nlink = cinfo.
links.size();
481 for(
int j=0;
j<nlink;
j++)
483 OpenHRP::LinkPosition& link_pos = char_pos.linkPositions[
j];
495 for(
int i=0;
i<nchar;
i++)
497 OpenHRP::SensorState&
state = all_sensor_states[
i];
500 int n_links = cinfo.
links.size();
501 for(
int j=0;
j<n_links;
j++)
508 state.q[index] = joint->
q;
509 state.dq[index] = joint->
qd;
510 state.u[index] = joint->
tau;
516 int n_sensors =
sensors.size();
517 for(
int i=0;
i<n_sensors;
i++)
530 case Sensor::RATE_GYRO:
537 case Sensor::ACCELERATION:
554 if(!cur || cur->
real)
return;
557 state.q[count] = cur->
q;
558 state.u[count] = cur->
tau;
566 const char* characterName,
567 const char* baseLink,
568 const char* targetLink,
581 for(
Joint*
j=targetj;
j!=basej;
j=
j->parent)
589 for(
Joint*
j=targetj;
j!=basej;
j=
j->parent)
591 for(
int m=0; m<
j->n_dof; m++)
593 J(0, count+m) = tempJ(0,
j->i_dof+m);
594 J(1, count+m) = tempJ(1,
j->i_dof+m);
595 J(2, count+m) = tempJ(2,
j->i_dof+m);
596 J(3, count+m) = tempJ(3,
j->i_dof+m);
597 J(4, count+m) = tempJ(4,
j->i_dof+m);
598 J(5, count+m) = tempJ(5,
j->i_dof+m);
607 double default_spring = 1e5;
608 double default_damper = 1e4;
609 double default_slip_p = 2000.0;
610 double default_slip_d = 700.0;
611 double default_slip_func_coef_base = 0.1;
612 SDContactPair* sd_pair =
new SDContactPair(jnt1, jnt2, default_spring, default_damper, staticFriction, slipFriction, default_slip_p, default_slip_d, default_slip_func_coef_base);
619 int n_links = links->length();
620 for(
int i=0;
i<n_links;
i++)
622 OpenHRP::LinkInfo linfo = links[
i];
626 cinfo.
links.push_back(jnt);
627 cinfo.
jointIDs.push_back(linfo.jointId);
628 if(linfo.jointId >= 0) cinfo.
n_joints++;
static std::ofstream logfile
static const bool debugMode
void setAllCharacterData(const char *name, OpenHRP::DynamicsSimulator::LinkDataType type, const OpenHRP::DblSequence &wdata)
std::vector< Sensor * > sensors
Joint * child
pointer to the child joint
int resize(int i, int j)
Changes the matrix size.
png_infop png_charp png_int_32 png_int_32 int * type
int CalcJacobian(fMat &J)
The Jacobian matrix of position/orientation w.r.t. the joint values.
void setGravityAcceleration(const fVec3 &g)
void _get_all_character_data_sub(Joint *cur, int index, OpenHRP::DynamicsSimulator::LinkDataType type, OpenHRP::DblSequence_out &rdata)
void set(const fMat33 &mat)
Copies a matrix.
void cross(const fVec3 &vec1, const fVec3 &vec2)
Cross product.
Forward dynamics computation based on Assembly-Disassembly Algorithm.
void addCharacter(Joint *rjoint, const std::string &_name, OpenHRP::LinkInfoSequence_var links)
png_infop png_charpp name
static void vec3_to_array(const fVec3 &vec, double *a, int offset=0)
void enableSensors(bool on)
fVec3 loc_ang_vel
angular velocity in local frame
fVec3 loc_lin_acc
linear acceleration in local frame
void getAllCharacterData(const char *name, OpenHRP::DynamicsSimulator::LinkDataType type, OpenHRP::DblSequence_out &rdata)
int Update()
Compute joint accelerations.
void set(double *v)
Set element values from array or three values.
int SetJointAcc(double _qdd)
Sensor * findSensor(const char *sensorName, const char *charName)
boost::shared_ptr< Body > BodyPtr
double q
joint value (for 1DOF joints)
double tau
joint force/torque (for 1DOF joints)
void calcNextState(OpenHRP::CollisionSequence &corbaCollisionSequence)
std::vector< Joint * > links
void zero()
Creates a zero matrix.
void CalcPosition()
Forward kinematics.
void _set_all_character_data_sub(Joint *cur, int index, OpenHRP::DynamicsSimulator::LinkDataType type, const OpenHRP::DblSequence &wdata)
int SetJointForce(double _tau)
double qd
joint velocity (for 1DOF joints)
int numRegisteredLinkPairs
def j(str, encoding="cp932")
JointType j_type
joint type
int NumDOF()
Total degrees of freedom.
static const double DEFAULT_GRAVITY_ACCELERATION
fMat33 abs_att
absolute orientation
char * CharName() const
Returns the character name.
void setRungeKuttaMethod()
void update_rate_gyro_sensor(RateGyroSensor *rgs)
char * name
joint name (including the character name)
std::vector< int > jointIDs
void neg(const fVec3 &vec)
int IntegrateRK4(double timestep, int step)
Performs 4-th order Runge-Kutta integration.
int addSensor(Joint *jnt, int sensorType, int id, const std::string name, const fVec3 &_localPos, const fMat33 &_localR)
Joint * brother
pointer to the brother joint
void getAllCharacterPositions(OpenHRP::CharacterPositionSequence &all_char_pos)
std::vector< CharacterInfo > characters
Joint * rootJoint(int index)
int SetJointValue(double _q)
double qdd
joint acceleration (for 1DOF joints)
void calcCharacterJacobian(const char *characterName, const char *baseLink, const char *targetLink, fMat &J)
void _get_all_sensor_states_sub(Joint *cur, int &count, OpenHRP::SensorState &state)
Joint * FindJoint(const char *jname, const char *charname=0)
Find a joint from name.
void addCollisionCheckLinkPair(Joint *jnt1, Joint *jnt2, double staticFriction, double slipFriction, double epsilon)
double * data()
Pointer to the first element.
int Schedule()
Creates default schedule, which is optimized for serial computation.
void setCurrentTime(double)
fVec3 abs_pos
absolute position
std::vector< SDContactPair * > contact_pairs
void mul(const fVec3 &vec, double d)
void update_accel_sensor(AccelSensor *as)
Main class for forward dynamics computation.
The class for representing a joint.
Joint * real
pointer to the real (connected) joint; for closed chains.
void update_force_sensor(ForceSensor *fs)
int SetJointVel(double _qd)
int Integrate(double timestep)
Performs Euler integration with timestep timestep [s].
fVec3 loc_ang_acc
angular acceleration in local frame
static void mat33_to_array(const fMat33 &mat, OpenHRP::DblArray9 &a)
Matrix of generic size. The elements are stored in a one-dimensional array in row-major order...
void getAllSensorStates(OpenHRP::SensorStateSequence &all_sensor_states)