Code-style consistency improvement:
Apply clang-format-all.sh using the _clang-format file through all the cpp/.h files. make sure not to apply it to certain serialization structures, since some parser expects the * as part of the name, instead of type. This commit contains no other changes aside from adding and applying clang-format-all.sh
This commit is contained in:
@@ -16,7 +16,7 @@ const int CONTROL_RATE = 500;
|
||||
|
||||
// Bullet globals
|
||||
b3PhysicsClientHandle kPhysClient = 0;
|
||||
const b3Scalar FIXED_TIMESTEP = 1.0/((b3Scalar)CONTROL_RATE);
|
||||
const b3Scalar FIXED_TIMESTEP = 1.0 / ((b3Scalar)CONTROL_RATE);
|
||||
// temp vars used a lot
|
||||
b3SharedMemoryCommandHandle command;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
@@ -25,9 +25,10 @@ b3JointInfo jointInfo;
|
||||
b3JointSensorState state;
|
||||
// test
|
||||
int twojoint;
|
||||
std::map< std::string, int > jointNameToId;
|
||||
std::map<std::string, int> jointNameToId;
|
||||
|
||||
int main(int argc, char* argv[]) {
|
||||
int main(int argc, char* argv[])
|
||||
{
|
||||
kPhysClient = b3CreateInProcessPhysicsServerAndConnect(argc, argv);
|
||||
if (!kPhysClient)
|
||||
return -1;
|
||||
@@ -54,7 +55,6 @@ int main(int argc, char* argv[]) {
|
||||
|
||||
b3Assert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED);
|
||||
|
||||
|
||||
// load test
|
||||
command = b3LoadUrdfCommandInit(kPhysClient, "TwoJointRobot_wo_fixedJoints.urdf");
|
||||
int flags = URDF_USE_INERTIA_FROM_FILE;
|
||||
@@ -66,26 +66,31 @@ int main(int argc, char* argv[]) {
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
b3Assert(statusType == CMD_URDF_LOADING_COMPLETED);
|
||||
if (statusType == CMD_URDF_LOADING_COMPLETED) {
|
||||
if (statusType == CMD_URDF_LOADING_COMPLETED)
|
||||
{
|
||||
twojoint = b3GetStatusBodyIndex(statusHandle);
|
||||
}
|
||||
|
||||
//disable default linear/angular damping
|
||||
b3SharedMemoryCommandHandle command = b3InitChangeDynamicsInfo(kPhysClient);
|
||||
double linearDamping = 0;
|
||||
double angularDamping = 0;
|
||||
b3ChangeDynamicsInfoSetLinearDamping(command, twojoint, linearDamping);
|
||||
b3ChangeDynamicsInfoSetAngularDamping(command, twojoint, angularDamping);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
|
||||
//disable default linear/angular damping
|
||||
b3SharedMemoryCommandHandle command = b3InitChangeDynamicsInfo(kPhysClient);
|
||||
double linearDamping = 0;
|
||||
double angularDamping = 0;
|
||||
b3ChangeDynamicsInfoSetLinearDamping(command, twojoint, linearDamping);
|
||||
b3ChangeDynamicsInfoSetAngularDamping(command, twojoint, angularDamping);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
|
||||
|
||||
int numJoints = b3GetNumJoints(kPhysClient, twojoint);
|
||||
printf("twojoint numjoints = %d\n", numJoints);
|
||||
// Loop through all joints
|
||||
for (int i=0; i<numJoints; ++i) {
|
||||
for (int i = 0; i < numJoints; ++i)
|
||||
{
|
||||
b3GetJointInfo(kPhysClient, twojoint, i, &jointInfo);
|
||||
if (jointInfo.m_jointName[0]) {
|
||||
if (jointInfo.m_jointName[0])
|
||||
{
|
||||
jointNameToId[std::string(jointInfo.m_jointName)] = i;
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
continue;
|
||||
}
|
||||
// Reset before torque control - see #1459
|
||||
@@ -96,15 +101,16 @@ int main(int argc, char* argv[]) {
|
||||
}
|
||||
|
||||
// loop
|
||||
unsigned long dtus1 = (unsigned long) 1000000.0*FIXED_TIMESTEP;
|
||||
unsigned long dtus1 = (unsigned long)1000000.0 * FIXED_TIMESTEP;
|
||||
double simTimeS = 0;
|
||||
double q[2], v[2];
|
||||
while (b3CanSubmitCommand(kPhysClient)) {
|
||||
simTimeS += 0.000001*dtus1;
|
||||
while (b3CanSubmitCommand(kPhysClient))
|
||||
{
|
||||
simTimeS += 0.000001 * dtus1;
|
||||
// apply some torque
|
||||
b3GetJointInfo(kPhysClient, twojoint, jointNameToId["joint_2"], &jointInfo);
|
||||
command = b3JointControlCommandInit2(kPhysClient, twojoint, CONTROL_MODE_TORQUE);
|
||||
b3JointControlSetDesiredForceTorque(command, jointInfo.m_uIndex, 0.5 * sin(10*simTimeS));
|
||||
b3JointControlSetDesiredForceTorque(command, jointInfo.m_uIndex, 0.5 * sin(10 * simTimeS));
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
|
||||
|
||||
// get joint values
|
||||
@@ -121,7 +127,7 @@ int main(int argc, char* argv[]) {
|
||||
|
||||
// debugging output
|
||||
printf("%.3f\t%.3f\t%.3f\t%.3f\t%.3f\n", simTimeS, q[0], q[1], v[0], v[1]);
|
||||
b3Clock::usleep(1000.*1000.*FIXED_TIMESTEP);
|
||||
b3Clock::usleep(1000. * 1000. * FIXED_TIMESTEP);
|
||||
}
|
||||
b3DisconnectSharedMemory(kPhysClient);
|
||||
return 0;
|
||||
|
||||
Reference in New Issue
Block a user