From 67a00a3a510ca53e6699bb9121d4c671b9e29e96 Mon Sep 17 00:00:00 2001 From: Yuval Tassa Date: Wed, 17 Jan 2024 04:33:00 -0800 Subject: [PATCH] Rename `mjMAXTHREADS` -> `mjMAXTHREAD` (consistency). PiperOrigin-RevId: 599130235 Change-Id: Ia80379b8ae0574a7cd8fbc668657f806e90d6c5c --- doc/APIreference/APIglobals.rst | 2 +- doc/includes/references.h | 2 +- include/mujoco/mjdata.h | 2 +- include/mujoco/mjthread.h | 2 +- include/mujoco/mjxmacro.h | 2 +- src/engine/engine_io.c | 2 +- src/thread/thread_pool.cc | 2 +- unity/Runtime/Bindings/MjBindings.cs | 2 +- 8 files changed, 8 insertions(+), 8 deletions(-) diff --git a/doc/APIreference/APIglobals.rst b/doc/APIreference/APIglobals.rst index 483383c40d..7e3778a575 100644 --- a/doc/APIreference/APIglobals.rst +++ b/doc/APIreference/APIglobals.rst @@ -489,7 +489,7 @@ shown in the table below. Their names are in the format ``mjKEY_XXX``. They corr - 1000 - Maximum number of textures allowed. Defined in `mjrender.h `_. - * - ``mjMAXTHREADS`` + * - ``mjMAXTHREAD`` - 128 - Maximum number OS threads that can be used in a thread pool. Defined in `mjthread.h `_. diff --git a/doc/includes/references.h b/doc/includes/references.h index 1c78815046..cfee19fb16 100644 --- a/doc/includes/references.h +++ b/doc/includes/references.h @@ -148,7 +148,7 @@ struct mjData_ { // memory utilization stats size_t maxuse_stack; // maximum stack allocation in bytes - size_t maxuse_threadstack[mjMAXTHREADS]; // maximum stack allocation per thread in bytes + size_t maxuse_threadstack[mjMAXTHREAD]; // maximum stack allocation per thread in bytes size_t maxuse_arena; // maximum arena allocation in bytes int maxuse_con; // maximum number of contacts int maxuse_efc; // maximum number of scalar constraints diff --git a/include/mujoco/mjdata.h b/include/mujoco/mjdata.h index 1fc6fe197b..53a4249845 100644 --- a/include/mujoco/mjdata.h +++ b/include/mujoco/mjdata.h @@ -176,7 +176,7 @@ struct mjData_ { // memory utilization stats size_t maxuse_stack; // maximum stack allocation in bytes - size_t maxuse_threadstack[mjMAXTHREADS]; // maximum stack allocation per thread in bytes + size_t maxuse_threadstack[mjMAXTHREAD]; // maximum stack allocation per thread in bytes size_t maxuse_arena; // maximum arena allocation in bytes int maxuse_con; // maximum number of contacts int maxuse_efc; // maximum number of scalar constraints diff --git a/include/mujoco/mjthread.h b/include/mujoco/mjthread.h index 9a526fa5e2..153ff0cce8 100644 --- a/include/mujoco/mjthread.h +++ b/include/mujoco/mjthread.h @@ -15,7 +15,7 @@ #ifndef MUJOCO_INCLUDE_MJTHREAD_H_ #define MUJOCO_INCLUDE_MJTHREAD_H_ -#define mjMAXTHREADS 128 // maximum number of threads in a thread pool +#define mjMAXTHREAD 128 // maximum number of threads in a thread pool typedef enum mjtTaskStatus_ { // status values for mjTask mjTASK_NEW = 0, // newly created diff --git a/include/mujoco/mjxmacro.h b/include/mujoco/mjxmacro.h index 86f61e0cb6..a46aea7159 100644 --- a/include/mujoco/mjxmacro.h +++ b/include/mujoco/mjxmacro.h @@ -739,7 +739,7 @@ // vector fields of mjData #define MJDATA_VECTOR \ - X( size_t, maxuse_threadstack, mjMAXTHREADS, 1 ) \ + X( size_t, maxuse_threadstack, mjMAXTHREAD, 1 ) \ X( mjWarningStat, warning, mjNWARNING, 1 ) \ X( mjTimerStat, timer, mjNTIMER, 1 ) \ X( mjSolverStat, solver, mjNILSAND, mjNSOLVER ) \ diff --git a/src/engine/engine_io.c b/src/engine/engine_io.c index ca55358aef..7c44b54f3b 100644 --- a/src/engine/engine_io.c +++ b/src/engine/engine_io.c @@ -1568,7 +1568,7 @@ static void _resetData(const mjModel* m, mjData* d, unsigned char debug_value) { // clear memory utilization stats d->maxuse_stack = 0; - mju_zeroSizeT(d->maxuse_threadstack, mjMAXTHREADS); + mju_zeroSizeT(d->maxuse_threadstack, mjMAXTHREAD); d->maxuse_arena = 0; d->maxuse_con = 0; d->maxuse_efc = 0; diff --git a/src/thread/thread_pool.cc b/src/thread/thread_pool.cc index 6c32c2b84e..9bb0313337 100644 --- a/src/thread/thread_pool.cc +++ b/src/thread/thread_pool.cc @@ -65,7 +65,7 @@ class ThreadPoolImpl : public mjThreadPool { public: ThreadPoolImpl(int num_worker) : mjThreadPool{num_worker} { // initialize worker threads - for (int i = 0; i < std::min(num_worker, mjMAXTHREADS); ++i) { + for (int i = 0; i < std::min(num_worker, mjMAXTHREAD); ++i) { WorkerThread worker{ std::make_unique(ThreadPoolWorker, this, i)}; workers_.push_back(std::move(worker)); diff --git a/unity/Runtime/Bindings/MjBindings.cs b/unity/Runtime/Bindings/MjBindings.cs index fd2c33bf90..1aeb7a12c5 100644 --- a/unity/Runtime/Bindings/MjBindings.cs +++ b/unity/Runtime/Bindings/MjBindings.cs @@ -58,7 +58,7 @@ public static class MujocoLib { public const int mjNAUX = 10; public const int mjMAXTEXTURE = 1000; public const bool THIRD_PARTY_MUJOCO_INCLUDE_MJTHREAD_H_ = true; -public const int mjMAXTHREADS = 128; +public const int mjMAXTHREAD = 128; public const bool THIRD_PARTY_MUJOCO_INCLUDE_MJTNUM_H_ = true; public const bool mjUSEDOUBLE = true; public const double mjMINVAL = 1e-15;