From 49ee1b26c681ec8d31a3a304ae9cbdcc5d2968c9 Mon Sep 17 00:00:00 2001 From: David Leins Date: Fri, 16 Feb 2024 14:54:49 +0100 Subject: [PATCH] chg: adds more real-time factors above 100% --- mujoco_ros/include/mujoco_ros/mujoco_env.h | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/mujoco_ros/include/mujoco_ros/mujoco_env.h b/mujoco_ros/include/mujoco_ros/mujoco_env.h index 6d5dad9..30c68dc 100644 --- a/mujoco_ros/include/mujoco_ros/mujoco_env.h +++ b/mujoco_ros/include/mujoco_ros/mujoco_env.h @@ -170,7 +170,7 @@ class MujocoEnv bool use_sim_time = true; // Sim speed - int real_time_index = 1; + int real_time_index = 8; int busywait = 0; // Mode @@ -237,10 +237,11 @@ class MujocoEnv */ int getOperationalStatus(); - static constexpr float percentRealTime[] = { -1, // unbound - 100, 80, 66, 50, 40, 33, 25, 20, 16, 13, 10, - 8, 6.6f, 5.0f, 4, 3.3f, 2.5f, 2, 1.6f, 1.3f, 1, .8f, - .66f, .5f, .4f, .33f, .25f, .2f, .16f, .13f, .1f }; + static constexpr float percentRealTime[] = { + -1, // unbound + 2000, 1000, 800, 600, 500, 400, 200, 150, 100, 80, 66, 50, 40, 33, 25, 20, 16, 13, 10, 8, + 6.6f, 5.0f, 4, 3.3f, 2.5f, 2, 1.6f, 1.3f, 1, .8f, .66f, .5f, .4f, .33f, .25f, .2f, .16f, .13f, .1f + }; static MujocoEnv *instance; static void proxyControlCB(const mjModel * /*m*/, mjData * /*d*/)