Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Implements vehicle damage based on kinetic energy #916

Merged
merged 16 commits into from
May 26, 2021
24 changes: 12 additions & 12 deletions subt_ign/include/subt_ign/RobotPlatformTypes.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,36 +23,36 @@ const std::map<std::string, double> robotPlatformTypes = {
{"ALLIE", 1},
{"ANYMAL_B", 1},
{"ANYMAL_C", 1},
{"CRYSTAL", 1},
{"DS1", 1},
{"CRYSTAL", 8}, // UAV, no prop guards
{"DS1", 6}, // UAV, prop guards
{"DTR", 1},
{"FREYJA", 1},
{"GAGARIN", 1},
{"GAGARIN", 6}, // UAV, prop guards
{"HD2", 1},
{"HOVERMAP", 1},
{"HOVERMAP", 6}, // UAV, prop guards
{"HUSKY", 1},
{"JEANINE", 1},
{"KAREN", 1},
{"KLOUBAK", 1},
{"LILY", 1},
{"M100", 1},
{"M100", 8}, // UAV, no prop guards
{"MARV", 1},
{"MIKE", 1},
{"OZBOT_ATR", 1},
{"PAM", 1},
{"QAV500", 1},
{"PAM", 6}, // UAV, prop guards
{"QAV500", 6}, // UAV, prop guards
{"R2", 1},
{"R3", 1},
{"RMF", 1},
{"RMF", 6}, // UAV, prop guards
{"ROCKY", 1},
{"SHAFTER", 1},
{"SHAFTER", 8}, // UAV, no prop guards
{"SPOT", 1},
{"TEAMBASE", 1},
{"X1", 1},
{"X2", 1},
{"X3", 7.2},
{"X4", 7.2},
{"X500", 14}
{"X3", 8}, // UAV, no prop guards
{"X6", 8}, // UAV, no prop guards
nkoenig marked this conversation as resolved.
Show resolved Hide resolved
{"X500", 8} // UAV, no prop guards
};

#endif
13 changes: 7 additions & 6 deletions subt_ign/src/GameLogicPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1168,18 +1168,19 @@ void GameLogicPlugin::PreUpdate(const UpdateInfo &_info,
double deltaKE = ke.second.prevKineticEnergy - currKineticEnergy;

// Debug: Compute the factor needed to hit the threshold.
if (deltaKE > 0.01)
{
double factor = ke.second.kineticEnergyThreshold / deltaKE;
std::cout << "KE[" << deltaKE << "] Thresh[" << ke.second.kineticEnergyThreshold << "] Factor[" << factor << "]\n";
}
// if (deltaKE > 0.01)
// {
// double factor = ke.second.kineticEnergyThreshold / deltaKE;
// std::cout << "KE[" << deltaKE << "] Thresh["
// << ke.second.kineticEnergyThreshold << "] Factor["
// << factor << "]\n";
// }

// Apply KE factor.
deltaKE *= robotPlatformTypes.at(
this->dataPtr->robotFullTypes[ke.second.robotName].first);
ke.second.prevKineticEnergy = currKineticEnergy;


// Crash if past the threshold.
if (ke.second.kineticEnergyThreshold > 0 &&
deltaKE >= ke.second.kineticEnergyThreshold)
Expand Down