Skip to content

Commit

Permalink
Merge pull request #3979 from gateway240/make-unique
Browse files Browse the repository at this point in the history
Use `std::make_unique` in wrapper function
adamkewley authored Dec 16, 2024

Verified

This commit was created on GitHub.com and signed with GitHub’s verified signature.
2 parents aaab82c + 93b061c commit c3e3ace
Showing 37 changed files with 87 additions and 94 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -51,6 +51,7 @@ v4.6
The original behavior (no trimming) can be enabled via the new property `trim_to_original_time_range`. (#3969)
- Make `InverseKinematicsSolver` methods to query for specific marker or orientation-sensor errors more robust to invalid names or names not
in the intersection of names in the model and names in the provided referece/data. Remove methods that are index based from public interface.(#3951)
- Replace usages of `OpenSim::make_unique` with `std::make_unique` and remove wrapper function now that C++14 is used in OpenSim (#3979).



2 changes: 1 addition & 1 deletion OpenSim/Actuators/DeGrooteFregly2016Muscle.cpp
Original file line number Diff line number Diff line change
@@ -944,7 +944,7 @@ void DeGrooteFregly2016Muscle::replaceMuscles(

// Pre-emptively create a default DeGrooteFregly2016Muscle
// (TODO: not ideal to do this).
auto actu = OpenSim::make_unique<DeGrooteFregly2016Muscle>();
auto actu = std::make_unique<DeGrooteFregly2016Muscle>();

// Perform muscle-model-specific mappings or throw exception if the
// muscle is not supported.
2 changes: 1 addition & 1 deletion OpenSim/Actuators/ModelFactory.cpp
Original file line number Diff line number Diff line change
@@ -165,7 +165,7 @@ void ModelFactory::replaceMusclesWithPathActuators(OpenSim::Model &model) {
auto& muscleSet = model.updMuscles();
for (int im = 0; im < muscleSet.getSize(); ++im) {
auto& musc = muscleSet.get(im);
auto actu = OpenSim::make_unique<PathActuator>();
auto actu = std::make_unique<PathActuator>();
actu->setName(musc.getName());
musc.setName(musc.getName() + "_delete");
actu->set_appliesForce(musc.get_appliesForce());
2 changes: 1 addition & 1 deletion OpenSim/Actuators/PolynomialPathFitter.cpp
Original file line number Diff line number Diff line change
@@ -1029,7 +1029,7 @@ Set<FunctionBasedPath> PolynomialPathFitter::fitPolynomialCoefficients(
lengthFunction.setDimension(numCoordinatesThisForce);
lengthFunction.setOrder(order);
lengthFunction.setCoefficients(coefficients);
auto functionBasedPath = make_unique<FunctionBasedPath>();
auto functionBasedPath = std::make_unique<FunctionBasedPath>();
functionBasedPath->setName(forcePath);
functionBasedPath->setCoordinatePaths(coordinatePathsThisForce);
functionBasedPath->setLengthFunction(lengthFunction);
8 changes: 0 additions & 8 deletions OpenSim/Common/CommonUtilities.h
Original file line number Diff line number Diff line change
@@ -36,14 +36,6 @@

namespace OpenSim {

/// Since OpenSim does not require C++14 (which contains std::make_unique()),
/// here is an implementation of make_unique().
/// @ingroup commonutil
template <typename T, typename... Args>
std::unique_ptr<T> make_unique(Args&&... args) {
return std::unique_ptr<T>(new T(std::forward<Args>(args)...));
}

/// Get a string with the current date and time formatted as %Y-%m-%dT%H%M%S
/// (year, month, day, "T", hour, minute, second). You can change the datetime
/// format via the `format` parameter.
4 changes: 2 additions & 2 deletions OpenSim/Common/TableUtilities.cpp
Original file line number Diff line number Diff line change
@@ -187,7 +187,7 @@ void TableUtilities::pad(
namespace {
template <typename FunctionType>
std::unique_ptr<FunctionSet> createFunctionSet(const TimeSeriesTable& table) {
auto set = make_unique<FunctionSet>();
auto set = std::make_unique<FunctionSet>();
const auto& time = table.getIndependentColumn();
const auto numRows = (int)table.getNumRows();
for (int icol = 0; icol < (int)table.getNumColumns(); ++icol) {
@@ -202,7 +202,7 @@ template <>
inline std::unique_ptr<FunctionSet> createFunctionSet<GCVSpline>(
const TimeSeriesTable& table) {
const auto& time = table.getIndependentColumn();
return OpenSim::make_unique<GCVSplineSet>(table, std::vector<std::string>{},
return std::make_unique<GCVSplineSet>(table, std::vector<std::string>{},
std::min((int)time.size() - 1, 5));
}
} // namespace
Original file line number Diff line number Diff line change
@@ -161,7 +161,7 @@ int main() {
{
MocoStudy study;
auto& problem = study.updProblem();
auto model = OpenSim::make_unique<Model>();
auto model = std::make_unique<Model>();
model->addComponent(new MyImplicitAuxiliaryDynamics("implicit"));
problem.setModel(std::move(model));
problem.setTimeBounds(0, 1.0);
Original file line number Diff line number Diff line change
@@ -29,7 +29,7 @@ using namespace OpenSim;
/// This model is torque-actuated.
std::unique_ptr<Model> createDoublePendulumModel() {
// This function is similar to ModelFactory::createNLinkPendulum().
auto model = make_unique<Model>();
auto model = std::make_unique<Model>();
model->setName("double_pendulum");

using SimTK::Vec3;
Original file line number Diff line number Diff line change
@@ -53,7 +53,7 @@ using namespace OpenSim;
/// @endverbatim

std::unique_ptr<Model> createSlidingMassModel() {
auto model = make_unique<Model>();
auto model = std::make_unique<Model>();
model->setName("sliding_mass");
model->set_gravity(SimTK::Vec3(0, 0, 0));
auto* body = new Body("body", 2.0, SimTK::Vec3(0), SimTK::Inertia(0));
Original file line number Diff line number Diff line change
@@ -41,7 +41,7 @@
using namespace OpenSim;

std::unique_ptr<Model> createSlidingMassModel() {
auto model = make_unique<Model>();
auto model = std::make_unique<Model>();
model->setName("sliding_mass");
model->set_gravity(SimTK::Vec3(0, 0, 0));
auto* body = new Body("body", 2.0, SimTK::Vec3(0), SimTK::Inertia(0));
Original file line number Diff line number Diff line change
@@ -42,7 +42,7 @@
using namespace OpenSim;

std::unique_ptr<Model> createSlidingMassModel() {
auto model = make_unique<Model>();
auto model = std::make_unique<Model>();
model->setName("sliding_mass");
model->set_gravity(SimTK::Vec3(0, 0, 0));
auto* body = new Body("body", 2.0, SimTK::Vec3(0), SimTK::Inertia(0));
2 changes: 1 addition & 1 deletion OpenSim/Examples/Moco/exampleTracking/exampleTracking.cpp
Original file line number Diff line number Diff line change
@@ -29,7 +29,7 @@ using namespace OpenSim;
std::unique_ptr<Model> createDoublePendulumModel() {
// This function is similar to ModelFactory::createNLinkPendulum().

auto model = make_unique<Model>();
auto model = std::make_unique<Model>();
model->setName("double_pendulum");

using SimTK::Vec3;
Original file line number Diff line number Diff line change
@@ -33,7 +33,7 @@
using namespace OpenSim;

std::unique_ptr<Model> createRocketModel() {
auto model = make_unique<Model>();
auto model = std::make_unique<Model>();
model->setName("sliding_mass");
model->set_gravity(SimTK::Vec3(9.81, 0, 0));
auto* body = new Body("body", 500000.0, SimTK::Vec3(0), SimTK::Inertia(0));
2 changes: 1 addition & 1 deletion OpenSim/Moco/Components/ControlDistributor.cpp
Original file line number Diff line number Diff line change
@@ -98,7 +98,7 @@ ControlDistributor::addControlDistributorAndConnectInputControllers(
"present in the model, but found '{}'.",
controlDistributor.getAbsolutePathString());
}
auto controlDistributorUPtr = make_unique<ControlDistributor>();
auto controlDistributorUPtr = std::make_unique<ControlDistributor>();
controlDistributorUPtr->setName("control_distributor");

const auto& output = controlDistributorUPtr->getOutput("controls");
2 changes: 1 addition & 1 deletion OpenSim/Moco/Components/ControlDistributor.h
Original file line number Diff line number Diff line change
@@ -41,7 +41,7 @@ namespace OpenSim {
*
* Constructing a ControlDistributor and adding controls:
* @code
* auto controlDistributor = make_unique<ControlDistributor>();
* auto controlDistributor = std::make_unique<ControlDistributor>();
* controlDistributor->addControl("/forceset/soleus_r");
* controlDistributor->addControl("/my_input_controller_value");
* controlDistributor->addControl("/my_custom_component_input");
22 changes: 11 additions & 11 deletions OpenSim/Moco/MocoCasADiSolver/CasOCProblem.h
Original file line number Diff line number Diff line change
@@ -260,11 +260,11 @@ class Problem {
OpenSim::Exception, "numIntegrals must be 0 or 1.");
std::unique_ptr<CostIntegrand> integrand_function;
if (numIntegrals) {
integrand_function = OpenSim::make_unique<CostIntegrand>();
integrand_function = std::make_unique<CostIntegrand>();
}
m_costInfos.emplace_back(std::move(name), numOutputs,
std::move(integrand_function),
OpenSim::make_unique<Cost>());
std::make_unique<Cost>());
}
/// Add an endpoint constraint to the problem.
void addEndpointConstraint(
@@ -274,7 +274,7 @@ class Problem {
std::unique_ptr<EndpointConstraintIntegrand> integrand_function;
if (numIntegrals) {
integrand_function =
OpenSim::make_unique<EndpointConstraintIntegrand>();
std::make_unique<EndpointConstraintIntegrand>();
}
casadi::DM lower(bounds.size(), 1);
casadi::DM upper(bounds.size(), 1);
@@ -284,7 +284,7 @@ class Problem {
}
m_endpointConstraintInfos.emplace_back(std::move(name),
(int)bounds.size(), std::move(integrand_function),
OpenSim::make_unique<EndpointConstraint>(), std::move(lower),
std::make_unique<EndpointConstraint>(), std::move(lower),
std::move(upper));
}
/// The size of bounds must match the number of outputs in the function.
@@ -296,7 +296,7 @@ class Problem {
upper(ibound, 0) = bounds[ibound].upper;
}
m_pathInfos.push_back({std::move(name), std::move(lower),
std::move(upper), OpenSim::make_unique<PathConstraint>()});
std::move(upper), std::make_unique<PathConstraint>()});
}
void setDynamicsMode(std::string dynamicsMode) {
OPENSIM_THROW_IF(
@@ -463,28 +463,28 @@ class Problem {
// Construct a full implicit multibody system (i.e. including
// kinematic constraints).
mutThis->m_implicitMultibodyFunc =
OpenSim::make_unique<MultibodySystemImplicit<true>>();
std::make_unique<MultibodySystemImplicit<true>>();
mutThis->m_implicitMultibodyFunc->constructFunction(this,
"implicit_multibody_system", finiteDiffScheme,
pointsForSparsityDetection);

// Construct an implicit multibody system ignoring kinematic
// constraints.
mutThis->m_implicitMultibodyFuncIgnoringConstraints =
OpenSim::make_unique<MultibodySystemImplicit<false>>();
std::make_unique<MultibodySystemImplicit<false>>();
mutThis->m_implicitMultibodyFuncIgnoringConstraints
->constructFunction(this,
"implicit_multibody_system_ignoring_constraints",
finiteDiffScheme, pointsForSparsityDetection);
} else {
mutThis->m_multibodyFunc =
OpenSim::make_unique<MultibodySystemExplicit<true>>();
std::make_unique<MultibodySystemExplicit<true>>();
mutThis->m_multibodyFunc->constructFunction(this,
"explicit_multibody_system", finiteDiffScheme,
pointsForSparsityDetection);

mutThis->m_multibodyFuncIgnoringConstraints =
OpenSim::make_unique<MultibodySystemExplicit<false>>();
std::make_unique<MultibodySystemExplicit<false>>();
mutThis->m_multibodyFuncIgnoringConstraints->constructFunction(this,
"multibody_system_ignoring_constraints", finiteDiffScheme,
pointsForSparsityDetection);
@@ -494,13 +494,13 @@ class Problem {
getNumKinematicConstraintEquations()) {
if (isKinematicConstraintMethodBordalba2023()) {
mutThis->m_stateProjectionFunc =
OpenSim::make_unique<StateProjection>();
std::make_unique<StateProjection>();
mutThis->m_stateProjectionFunc->constructFunction(this,
"state_projection", finiteDiffScheme,
pointsForSparsityDetection);
} else {
mutThis->m_velocityCorrectionFunc =
OpenSim::make_unique<VelocityCorrection>();
std::make_unique<VelocityCorrection>();
mutThis->m_velocityCorrectionFunc->constructFunction(this,
"velocity_correction", finiteDiffScheme,
pointsForSparsityDetection);
42 changes: 21 additions & 21 deletions OpenSim/Moco/MocoCasADiSolver/CasOCSolver.cpp
Original file line number Diff line number Diff line change
@@ -31,53 +31,53 @@ namespace CasOC {
std::unique_ptr<Transcription> Solver::createTranscription() const {
std::unique_ptr<Transcription> transcription;
if (m_transcriptionScheme == "trapezoidal") {
transcription = OpenSim::make_unique<Trapezoidal>(*this, m_problem);
transcription = std::make_unique<Trapezoidal>(*this, m_problem);
} else if (m_transcriptionScheme == "hermite-simpson") {
transcription = OpenSim::make_unique<HermiteSimpson>(*this, m_problem);
transcription = std::make_unique<HermiteSimpson>(*this, m_problem);
} else if (m_transcriptionScheme == "legendre-gauss-1") {
transcription = OpenSim::make_unique<LegendreGauss>(*this, m_problem, 1);
transcription = std::make_unique<LegendreGauss>(*this, m_problem, 1);
} else if (m_transcriptionScheme == "legendre-gauss-2") {
transcription = OpenSim::make_unique<LegendreGauss>(*this, m_problem, 2);
transcription = std::make_unique<LegendreGauss>(*this, m_problem, 2);
} else if (m_transcriptionScheme == "legendre-gauss-3") {
transcription = OpenSim::make_unique<LegendreGauss>(*this, m_problem, 3);
transcription = std::make_unique<LegendreGauss>(*this, m_problem, 3);
} else if (m_transcriptionScheme == "legendre-gauss-4") {
transcription = OpenSim::make_unique<LegendreGauss>(*this, m_problem, 4);
transcription = std::make_unique<LegendreGauss>(*this, m_problem, 4);
} else if (m_transcriptionScheme == "legendre-gauss-5") {
transcription = OpenSim::make_unique<LegendreGauss>(*this, m_problem, 5);
transcription = std::make_unique<LegendreGauss>(*this, m_problem, 5);
} else if (m_transcriptionScheme == "legendre-gauss-6") {
transcription = OpenSim::make_unique<LegendreGauss>(*this, m_problem, 6);
transcription = std::make_unique<LegendreGauss>(*this, m_problem, 6);
} else if (m_transcriptionScheme == "legendre-gauss-7") {
transcription = OpenSim::make_unique<LegendreGauss>(*this, m_problem, 7);
transcription = std::make_unique<LegendreGauss>(*this, m_problem, 7);
} else if (m_transcriptionScheme == "legendre-gauss-8") {
transcription = OpenSim::make_unique<LegendreGauss>(*this, m_problem, 8);
transcription = std::make_unique<LegendreGauss>(*this, m_problem, 8);
} else if (m_transcriptionScheme == "legendre-gauss-9") {
transcription = OpenSim::make_unique<LegendreGauss>(*this, m_problem, 9);
transcription = std::make_unique<LegendreGauss>(*this, m_problem, 9);
} else if (m_transcriptionScheme == "legendre-gauss-radau-1") {
transcription = OpenSim::make_unique<LegendreGaussRadau>(
transcription = std::make_unique<LegendreGaussRadau>(
*this, m_problem, 1);
} else if (m_transcriptionScheme == "legendre-gauss-radau-2") {
transcription = OpenSim::make_unique<LegendreGaussRadau>(
transcription = std::make_unique<LegendreGaussRadau>(
*this, m_problem, 2);
} else if (m_transcriptionScheme == "legendre-gauss-radau-3") {
transcription = OpenSim::make_unique<LegendreGaussRadau>(
transcription = std::make_unique<LegendreGaussRadau>(
*this, m_problem, 3);
} else if (m_transcriptionScheme == "legendre-gauss-radau-4") {
transcription = OpenSim::make_unique<LegendreGaussRadau>(
transcription = std::make_unique<LegendreGaussRadau>(
*this, m_problem, 4);
} else if (m_transcriptionScheme == "legendre-gauss-radau-5") {
transcription = OpenSim::make_unique<LegendreGaussRadau>(
transcription = std::make_unique<LegendreGaussRadau>(
*this, m_problem, 5);
} else if (m_transcriptionScheme == "legendre-gauss-radau-6") {
transcription = OpenSim::make_unique<LegendreGaussRadau>(
transcription = std::make_unique<LegendreGaussRadau>(
*this, m_problem, 6);
} else if (m_transcriptionScheme == "legendre-gauss-radau-7") {
transcription = OpenSim::make_unique<LegendreGaussRadau>(
transcription = std::make_unique<LegendreGaussRadau>(
*this, m_problem, 7);
} else if (m_transcriptionScheme == "legendre-gauss-radau-8") {
transcription = OpenSim::make_unique<LegendreGaussRadau>(
transcription = std::make_unique<LegendreGaussRadau>(
*this, m_problem, 8);
} else if (m_transcriptionScheme == "legendre-gauss-radau-9") {
transcription = OpenSim::make_unique<LegendreGaussRadau>(
transcription = std::make_unique<LegendreGaussRadau>(
*this, m_problem, 9);
} else {
OPENSIM_THROW(Exception, "Unknown transcription scheme '{}'.",
@@ -132,7 +132,7 @@ Solution Solver::solve(const Iterate& guess) const {
pointsForSparsityDetection->push_back(guessCopy.variables);
} else if (m_sparsity_detection == "random") {
// Make sure the exact same sparsity pattern is used every time.
auto randGen = OpenSim::make_unique<SimTK::Random::Uniform>(-1, 1);
auto randGen = std::make_unique<SimTK::Random::Uniform>(-1, 1);
randGen->setSeed(0);
for (int i = 0; i < m_sparsity_detection_random_count; ++i) {
pointsForSparsityDetection->push_back(
4 changes: 2 additions & 2 deletions OpenSim/Moco/MocoCasADiSolver/MocoCasADiSolver.cpp
Original file line number Diff line number Diff line change
@@ -194,7 +194,7 @@ std::unique_ptr<MocoCasOCProblem> MocoCasADiSolver::createCasOCProblem() const {
"but received '{}'.", get_transcription_scheme());
}

return OpenSim::make_unique<MocoCasOCProblem>(*this, problemRep,
return std::make_unique<MocoCasOCProblem>(*this, problemRep,
createProblemRepJar(numThreads), get_multibody_dynamics_mode(),
get_kinematic_constraint_method());
#else
@@ -205,7 +205,7 @@ std::unique_ptr<MocoCasOCProblem> MocoCasADiSolver::createCasOCProblem() const {
std::unique_ptr<CasOC::Solver> MocoCasADiSolver::createCasOCSolver(
const MocoCasOCProblem& casProblem) const {
#ifdef OPENSIM_WITH_CASADI
auto casSolver = OpenSim::make_unique<CasOC::Solver>(casProblem);
auto casSolver = std::make_unique<CasOC::Solver>(casProblem);

// Set solver options.
// -------------------
2 changes: 1 addition & 1 deletion OpenSim/Moco/MocoCasADiSolver/MocoCasOCProblem.cpp
Original file line number Diff line number Diff line change
@@ -281,7 +281,7 @@ MocoCasOCProblem::MocoCasOCProblem(const MocoCasADiSolver& mocoCasADiSolver,
addPathConstraint(name, casBounds);
}

m_fileDeletionThrower = OpenSim::make_unique<FileDeletionThrower>(
m_fileDeletionThrower = std::make_unique<FileDeletionThrower>(
fmt::format("delete_this_to_stop_optimization_{}_{}.txt",
problemRep.getName(), m_formattedTimeString));
}
2 changes: 1 addition & 1 deletion OpenSim/Moco/MocoGoal/MocoContactImpulseTrackingGoal.cpp
Original file line number Diff line number Diff line change
@@ -116,7 +116,7 @@ void MocoContactImpulseTrackingGoal::initializeOnModelImpl(const Model& model) c
extLoads = &get_external_loads();
}
else if (!get_external_loads_file().empty()) {
extLoadsFromFile = OpenSim::make_unique<ExternalLoads>(
extLoadsFromFile = std::make_unique<ExternalLoads>(
get_external_loads_file(), true);
extLoads = extLoadsFromFile.get();
}
2 changes: 1 addition & 1 deletion OpenSim/Moco/MocoGoal/MocoContactTrackingGoal.cpp
Original file line number Diff line number Diff line change
@@ -123,7 +123,7 @@ void MocoContactTrackingGoal::initializeOnModelImpl(const Model& model) const {
"were provided.");
extLoads = &get_external_loads();
} else if (!get_external_loads_file().empty()) {
extLoadsFromFile = OpenSim::make_unique<ExternalLoads>(
extLoadsFromFile = std::make_unique<ExternalLoads>(
get_external_loads_file(), true);
extLoads = extLoadsFromFile.get();
} else {
Loading

0 comments on commit c3e3ace

Please sign in to comment.