update MinitaurSetup.cpp/h to allow switching between different minitaurs. add getToeForces, thanks to Avik (requires 8 toes!)

This commit is contained in:
erwincoumans 2018-01-09 17:38:51 -08:00
parent 15a429f1bf
commit 616d3358bd
2 changed files with 200 additions and 43 deletions

View File

@ -37,6 +37,126 @@ void MinitaurSetup::setDesiredMotorAngle(class b3RobotSimulatorClientAPI* sim, c
sim->setJointMotorControl(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[motorName],controlArgs); sim->setJointMotorControl(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[motorName],controlArgs);
} }
//pick exactly 1 configuration of the following
#define MINITAUR_RAINBOWDASH_V1
//#define MINITAUR_RAINBOWDASH_V0
//#define MINITAUR_V0
#if defined(MINITAUR_RAINBOWDASH_V1)
#define MINITAUR_HAS_DEFORMABLE_BRACKETS
static const char* minitaurURDF="quadruped/minitaur_rainbow_dash_v1.urdf";
static const char* kneeNames[]={
"knee_front_leftL_joint",//1
"knee_front_leftR_joint",//3
"knee_back_leftL_joint",//5
"knee_back_leftR_joint",//7
"knee_front_rightL_joint",//9
"knee_back_rightL_joint",//10
"knee_back_rightR_joint",//13
"knee_front_rightR_joint",//15
};
static const char* motorNames[]={
"motor_front_leftL_joint",//0
"knee_front_leftL_joint",//1
"motor_front_leftR_joint",//2
"knee_front_leftR_joint",//3
"motor_back_leftL_joint",//4
"knee_back_leftL_joint",//5
"motor_back_leftR_joint",//6
"knee_back_leftR_joint",//7
"motor_front_rightL_joint",//8
"knee_front_rightL_joint",//9
"knee_back_rightL_joint",//10
"motor_back_rightL_joint",//11
"motor_back_rightR_joint",//12
"knee_back_rightR_joint",//13
"motor_front_rightR_joint",//14
"knee_front_rightR_joint",//15
};
static const char* bracketNames[] = {
"motor_front_rightR_bracket_joint",
"motor_front_leftL_bracket_joint",
"motor_back_rightR_bracket_joint",
"motor_back_leftL_bracket_joint",
};
static b3Vector3 KNEE_CONSTRAINT_POINT_LONG = b3MakeVector3(0, 0.0045, 0.088);
static b3Vector3 KNEE_CONSTRAINT_POINT_SHORT= b3MakeVector3(0, 0.0045, 0.100);
#elif defined(MINITAUR_RAINBOWDASH_V0)
static const char* minitaurURDF="quadruped/minitaur_rainbow_dash.urdf";
static const char* kneeNames[]={
"knee_front_leftL_joint",//1
"knee_front_leftR_joint",//3
"knee_back_leftL_joint",//5
"knee_back_leftR_joint",//7
"knee_front_rightL_joint",//9
"knee_back_rightL_joint",//10
"knee_back_rightR_joint",//13
"knee_front_rightR_joint",//15
};
static const char* motorNames[]={
"motor_front_leftL_joint",//0
"knee_front_leftL_joint",//1
"motor_front_leftR_joint",//2
"knee_front_leftR_joint",//3
"motor_back_leftL_joint",//4
"knee_back_leftL_joint",//5
"motor_back_leftR_joint",//6
"knee_back_leftR_joint",//7
"motor_front_rightL_joint",//8
"knee_front_rightL_joint",//9
"knee_back_rightL_joint",//10
"motor_back_rightL_joint",//11
"motor_back_rightR_joint",//12
"knee_back_rightR_joint",//13
"motor_front_rightR_joint",//14
"knee_front_rightR_joint",//15
};
static b3Vector3 KNEE_CONSTRAINT_POINT_LONG = b3MakeVector3(0, 0.0045, 0.088);
static b3Vector3 KNEE_CONSTRAINT_POINT_SHORT= b3MakeVector3(0, 0.0045, 0.100);
#elif defined(MINITAUR_V0)
static const char* minitaurURDF="quadruped/minitaur.urdf";
static const char* kneeNames[]={
"knee_front_leftL_link",
"knee_front_leftR_link",
"knee_back_leftL_link",
"knee_back_leftR_link",
"knee_front_rightL_link",
"knee_back_rightL_link",
"knee_back_rightR_link",
"knee_front_rightR_link",
};
static const char* motorNames[]={
"motor_front_leftL_joint",
"knee_front_leftL_link",
"motor_front_leftR_joint",
"knee_front_leftR_link",
"motor_back_leftL_joint",
"knee_back_leftL_link",
"motor_back_leftR_joint",
"knee_back_leftR_link",
"motor_front_rightL_joint",
"knee_front_rightL_link",
"knee_back_rightL_link",
"motor_back_rightL_joint",
"motor_back_rightR_joint",
"knee_back_rightR_link",
"motor_front_rightR_joint",
"knee_front_rightR_link",
};
static b3Vector3 KNEE_CONSTRAINT_POINT_LONG = b3MakeVector3(0, 0.005, 0.2);
static b3Vector3 KNEE_CONSTRAINT_POINT_SHORT= b3MakeVector3(0, 0.01, 0.2);
#endif
void MinitaurSetup::resetPose(class b3RobotSimulatorClientAPI* sim) void MinitaurSetup::resetPose(class b3RobotSimulatorClientAPI* sim)
{ {
@ -58,59 +178,80 @@ void MinitaurSetup::resetPose(class b3RobotSimulatorClientAPI* sim)
b3JointInfo jointInfo; b3JointInfo jointInfo;
jointInfo.m_jointType = ePoint2PointType; jointInfo.m_jointType = ePoint2PointType;
//left front leg //left front leg
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_leftL_joint"],motorDirs[0] * startAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[motorNames[0]],motorDirs[0] * startAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_leftL_link"],motorDirs[0]*kneeAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[0]],motorDirs[0]*kneeAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_leftR_joint"],motorDirs[1] * startAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[motorNames[2]],motorDirs[1] * startAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_leftR_link"],motorDirs[1]*kneeAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[1]],motorDirs[1]*kneeAngle);
jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = 0.005; jointInfo.m_parentFrame[2] = 0.2; jointInfo.m_parentFrame[0] = KNEE_CONSTRAINT_POINT_SHORT[0]; jointInfo.m_parentFrame[1] = KNEE_CONSTRAINT_POINT_SHORT[1]; jointInfo.m_parentFrame[2] = KNEE_CONSTRAINT_POINT_SHORT[2];
jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = 0.01; jointInfo.m_childFrame[2] = 0.2; jointInfo.m_childFrame[0] = KNEE_CONSTRAINT_POINT_LONG[0]; jointInfo.m_childFrame[1] = KNEE_CONSTRAINT_POINT_LONG[1]; jointInfo.m_childFrame[2] = KNEE_CONSTRAINT_POINT_LONG[2];
sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_leftR_link"],
m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_leftL_link"],&jointInfo); //jointInfo.m_parentFrame[0] = KNEE_CONSTRAINT_POINT_LONG[0]; jointInfo.m_parentFrame[1] = KNEE_CONSTRAINT_POINT_LONG[1]; jointInfo.m_parentFrame[2] = KNEE_CONSTRAINT_POINT_LONG[2];
setDesiredMotorAngle(sim,"motor_front_leftL_joint", motorDirs[0] * startAngle); //jointInfo.m_childFrame[0] = KNEE_CONSTRAINT_POINT_SHORT[0]; jointInfo.m_childFrame[1] = KNEE_CONSTRAINT_POINT_SHORT[1]; jointInfo.m_childFrame[2] = KNEE_CONSTRAINT_POINT_SHORT[2];
setDesiredMotorAngle(sim,"motor_front_leftR_joint", motorDirs[1] * startAngle); sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[1]],
m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[0]],&jointInfo);
setDesiredMotorAngle(sim,motorNames[0], motorDirs[0] * startAngle);
setDesiredMotorAngle(sim,motorNames[2], motorDirs[1] * startAngle);
//left back leg //left back leg
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_leftL_joint"],motorDirs[2] * startAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[motorNames[4]],motorDirs[2] * startAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_leftL_link"],motorDirs[2] * kneeAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[2]],motorDirs[2] * kneeAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_leftR_joint"],motorDirs[3] * startAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[motorNames[6]],motorDirs[3] * startAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_leftR_link"],motorDirs[3] * kneeAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[3]],motorDirs[3] * kneeAngle);
jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = 0.005; jointInfo.m_parentFrame[2] = 0.2; jointInfo.m_parentFrame[0] = KNEE_CONSTRAINT_POINT_SHORT[0]; jointInfo.m_parentFrame[1] = KNEE_CONSTRAINT_POINT_SHORT[1]; jointInfo.m_parentFrame[2] = KNEE_CONSTRAINT_POINT_SHORT[2];
jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = 0.01; jointInfo.m_childFrame[2] = 0.2; jointInfo.m_childFrame[0] = KNEE_CONSTRAINT_POINT_LONG[0]; jointInfo.m_childFrame[1] = KNEE_CONSTRAINT_POINT_LONG[1]; jointInfo.m_childFrame[2] = KNEE_CONSTRAINT_POINT_LONG[2];
sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_leftR_link"],
m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_leftL_link"],&jointInfo); //jointInfo.m_parentFrame[0] = KNEE_CONSTRAINT_POINT_LONG[0]; jointInfo.m_parentFrame[1] = KNEE_CONSTRAINT_POINT_LONG[1]; jointInfo.m_parentFrame[2] = KNEE_CONSTRAINT_POINT_LONG[2];
setDesiredMotorAngle(sim,"motor_back_leftL_joint", motorDirs[2] * startAngle); //jointInfo.m_childFrame[0] = KNEE_CONSTRAINT_POINT_SHORT[0]; jointInfo.m_childFrame[1] = KNEE_CONSTRAINT_POINT_SHORT[1]; jointInfo.m_childFrame[2] = KNEE_CONSTRAINT_POINT_SHORT[2];
setDesiredMotorAngle(sim,"motor_back_leftR_joint", motorDirs[3] * startAngle); sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[3]],
m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[2]],&jointInfo);
setDesiredMotorAngle(sim,motorNames[4], motorDirs[2] * startAngle);
setDesiredMotorAngle(sim,motorNames[6], motorDirs[3] * startAngle);
//right front leg //right front leg
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_rightL_joint"],motorDirs[4] * startAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[motorNames[8]],motorDirs[4] * startAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightL_link"],motorDirs[4] * kneeAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[4]],motorDirs[4] * kneeAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_front_rightR_joint"],motorDirs[5]*startAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[motorNames[14]],motorDirs[5]*startAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightR_link"],motorDirs[5] * kneeAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[7]],motorDirs[5] * kneeAngle);
jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = 0.005; jointInfo.m_parentFrame[2] = 0.2; jointInfo.m_parentFrame[0] = KNEE_CONSTRAINT_POINT_LONG[0]; jointInfo.m_parentFrame[1] = KNEE_CONSTRAINT_POINT_LONG[1]; jointInfo.m_parentFrame[2] = KNEE_CONSTRAINT_POINT_LONG[2];
jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = 0.01; jointInfo.m_childFrame[2] = 0.2; jointInfo.m_childFrame[0] = KNEE_CONSTRAINT_POINT_SHORT[0]; jointInfo.m_childFrame[1] = KNEE_CONSTRAINT_POINT_SHORT[1]; jointInfo.m_childFrame[2] = KNEE_CONSTRAINT_POINT_SHORT[2];
sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightR_link"], sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[7]],
m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_front_rightL_link"],&jointInfo); m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[4]],&jointInfo);
setDesiredMotorAngle(sim,"motor_front_rightL_joint",motorDirs[4] * startAngle); setDesiredMotorAngle(sim,motorNames[8],motorDirs[4] * startAngle);
setDesiredMotorAngle(sim,"motor_front_rightR_joint",motorDirs[5] * startAngle); setDesiredMotorAngle(sim,motorNames[14],motorDirs[5] * startAngle);
//right back leg //right back leg
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_rightL_joint"],motorDirs[6] * startAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[motorNames[11]],motorDirs[6] * startAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightL_link"],motorDirs[6] * kneeAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[5]],motorDirs[6] * kneeAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["motor_back_rightR_joint"],motorDirs[7] * startAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[motorNames[12]],motorDirs[7] * startAngle);
sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightR_link"],motorDirs[7] * kneeAngle); sim->resetJointState(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[6]],motorDirs[7] * kneeAngle);
jointInfo.m_parentFrame[0] = 0; jointInfo.m_parentFrame[1] = 0.005; jointInfo.m_parentFrame[2] = 0.2; jointInfo.m_parentFrame[0] = KNEE_CONSTRAINT_POINT_LONG[0]; jointInfo.m_parentFrame[1] = KNEE_CONSTRAINT_POINT_LONG[1]; jointInfo.m_parentFrame[2] = KNEE_CONSTRAINT_POINT_LONG[2];
jointInfo.m_childFrame[0] = 0; jointInfo.m_childFrame[1] = 0.01; jointInfo.m_childFrame[2] = 0.2; jointInfo.m_childFrame[0] = KNEE_CONSTRAINT_POINT_SHORT[0]; jointInfo.m_childFrame[1] = KNEE_CONSTRAINT_POINT_SHORT[1]; jointInfo.m_childFrame[2] = KNEE_CONSTRAINT_POINT_SHORT[2];
sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightR_link"], sim->createConstraint(m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[6]],
m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId["knee_back_rightL_link"],&jointInfo); m_data->m_quadrupedUniqueId,*m_data->m_jointNameToId[kneeNames[5]],&jointInfo);
setDesiredMotorAngle(sim,"motor_back_rightL_joint", motorDirs[6] * startAngle); setDesiredMotorAngle(sim,motorNames[11], motorDirs[6] * startAngle);
setDesiredMotorAngle(sim,"motor_back_rightR_joint", motorDirs[7] * startAngle); setDesiredMotorAngle(sim,motorNames[12], motorDirs[7] * startAngle);
#ifdef MINITAUR_HAS_DEFORMABLE_BRACKETS
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
controlArgs.m_maxTorqueValue = 6;
controlArgs.m_kd = 1;
controlArgs.m_kp = 0;
controlArgs.m_targetPosition = 0;
for (int i=0;i<4;i++)
{
const char* bracketName = bracketNames[i];
int* bracketId =m_data->m_jointNameToId[bracketName];
sim->setJointMotorControl(m_data->m_quadrupedUniqueId,*bracketId,controlArgs);
}
#endif
} }
@ -121,8 +262,8 @@ int MinitaurSetup::setupMinitaur(class b3RobotSimulatorClientAPI* sim, const b3V
args.m_startPosition = startPos; args.m_startPosition = startPos;
args.m_startOrientation = startOrn; args.m_startOrientation = startOrn;
m_data->m_quadrupedUniqueId = sim->loadURDF("quadruped/minitaur.urdf",args); m_data->m_quadrupedUniqueId = sim->loadURDF(minitaurURDF,args);
int numJoints = sim->getNumJoints(m_data->m_quadrupedUniqueId); int numJoints = sim->getNumJoints(m_data->m_quadrupedUniqueId);
for (int i=0;i<numJoints;i++) for (int i=0;i<numJoints;i++)
{ {
@ -138,3 +279,17 @@ int MinitaurSetup::setupMinitaur(class b3RobotSimulatorClientAPI* sim, const b3V
return m_data->m_quadrupedUniqueId; return m_data->m_quadrupedUniqueId;
} }
int MinitaurSetup::getToeForces(class b3RobotSimulatorClientAPI* sim, int groundid, b3Vector3 normalForcesOut[4])
{
sim->getContactNormalForce(m_data->m_quadrupedUniqueId, *m_data->m_jointNameToId[kneeNames[0]], groundid, -1, &normalForcesOut[0]);
sim->getContactNormalForce(m_data->m_quadrupedUniqueId, *m_data->m_jointNameToId[kneeNames[2]], groundid, -1, &normalForcesOut[1]);
sim->getContactNormalForce(m_data->m_quadrupedUniqueId, *m_data->m_jointNameToId[kneeNames[4]], groundid, -1, &normalForcesOut[2]);
sim->getContactNormalForce(m_data->m_quadrupedUniqueId, *m_data->m_jointNameToId[kneeNames[5]], groundid, -1, &normalForcesOut[3]);
sim->getContactNormalForce(m_data->m_quadrupedUniqueId, *m_data->m_jointNameToId[kneeNames[1]], groundid, -1, &normalForcesOut[4]);
sim->getContactNormalForce(m_data->m_quadrupedUniqueId, *m_data->m_jointNameToId[kneeNames[3]], groundid, -1, &normalForcesOut[5]);
sim->getContactNormalForce(m_data->m_quadrupedUniqueId, *m_data->m_jointNameToId[kneeNames[6]], groundid, -1, &normalForcesOut[6]);
sim->getContactNormalForce(m_data->m_quadrupedUniqueId, *m_data->m_jointNameToId[kneeNames[7]], groundid, -1, &normalForcesOut[7]);
return 0;
}

View File

@ -16,6 +16,8 @@ public:
void setDesiredMotorAngle(class b3RobotSimulatorClientAPI* sim, const char* motorName, double desiredAngle, double maxTorque=3,double kp=0.1, double kd=0.9); void setDesiredMotorAngle(class b3RobotSimulatorClientAPI* sim, const char* motorName, double desiredAngle, double maxTorque=3,double kp=0.1, double kd=0.9);
// Added for testing
int getToeForces(class b3RobotSimulatorClientAPI* sim, int groundid, b3Vector3 normalForcesOut[4]);
}; };
#endif //MINITAUR_SIMULATION_SETUP_H #endif //MINITAUR_SIMULATION_SETUP_H