feat: add VirtualGantryPlugin — rope-constraint gantry for humanoid simulation#3
Conversation
Introduces a PD spring-damper plugin that holds a configurable body (default: torso_link) at its spawn-time world-frame position. Intended as a safety net during policy startup and after simulation resets, so humanoid robots do not fall before the locomotion policy is active. - mujoco_ros2_control_msgs: add SetGantryEnabled and SetGantryTarget service definitions (depends on geometry_msgs for Point) - mujoco_ros2_control_plugins: add VirtualGantryPlugin implementing the PD controller via xfrc_applied; exposes set_gantry_enabled and set_gantry_target ROS 2 services on the plugin sub-namespace Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
… stabilize PD gains - mujoco_system_interface: copy xfrc_applied from mj_data_control_ to mj_data_ at all three mj_step call sites, matching the existing pattern for ctrl and qfrc_applied. Without this the plugin forces were written to the control buffer but never reached the physics simulation. - mujoco_ros2_control_plugins_base: add virtual reset() hook (default no-op) so plugins can clear accumulated state on world reset. - VirtualGantryPlugin: fix xfrc_applied indices (+3..+5 were torques, forces are at +0..+2); defer spawn-position capture to first update() to avoid a race with mj_forward() in the physics thread; implement reset() to re-arm spawn capture on world reset; tune PD gains to kp=10000 kd=3000 for overdamped behaviour (ζ≈2.5) with ~3 cm steady-state gravity offset; clean up comments and unused parameters. Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Zero-dependency header-only singleton with two atomics: - toggle_counter: incremented by the GLFW adapter on each 'G' press - rope_scroll_ticks: accumulated Shift+scroll ticks VirtualGantryPlugin reads these in update() to toggle the gantry and adjust rope length without any mutex or inter-component coupling.
Replaces the PD spring-to-fixed-position with a one-sided cable constraint: - Anchor spawns anchor_height (2 m) directly above the configured attachment point on the first update() after enable or reset. - When distance from anchor to attachment exceeds rope_length, a radial-only tension force is applied toward the anchor. No lateral force is ever applied, so the robot swings freely like a pendulum. - Attachment point is configurable: body_name + body_offset (in body frame, default 0,0,0). - Keyboard toggle: reads GantryKeyboardState::toggle_counter each step; 'G' re-enables with a fresh anchor above the current position. - Rope length adjustment via GantryKeyboardState::rope_scroll_ticks (Shift+scroll, 5 cm per notch, minimum 0.1 m). - Rope capsule geom half-length updated each frame to match the current anchor-to-attachment distance.
- 'G' press increments GantryKeyboardState::toggle_counter (gantry on/off). - Shift+scroll accumulates ticks in GantryKeyboardState::rope_scroll_ticks (suppresses camera zoom while adjusting rope length).
Move GantryKeyboardState::get() from header to .cpp so both DSOs (mujoco_ros2_control and mujoco_ros2_control_plugins) share one instance rather than each getting their own -fvisibility=hidden-isolated static. Replace relative anchor_height with anchor_z_world (world-frame Z). Rope length is now computed at spawn as |anchor_z - attach_z| rather than read from YAML. Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
GlfwAdapter's scroll GLFW callback calls PlatformUIAdapter::OnScroll via a devirtualized direct call (R_X86_64_PLT32), so virtual OnScroll overrides in ROS2ControlGlfwAdapter are never reached for scroll events. Replace Shift+scroll with '[' (shorten) and ']' (lengthen) key presses that go through the virtual OnKey dispatch. Hold for key-repeat to adjust continuously. Rename rope_scroll_ticks to rope_length_ticks accordingly. Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
GantryKeyboardState::get() is defined in the plugins library. mujoco_ros2_control needs to link against it so the symbol is resolved at link time and both DSOs share the same singleton instance. Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
…ory registration
Placing the definition in libmujoco_ros2_control_plugins.so and directly linking
it from libmujoco_ros2_control.so caused the plugins DSO to be loaded at process
startup — before pluginlib ClassLoader initialises — so PLUGINLIB_EXPORT_CLASS
static constructors ran too early and VirtualGantryPlugin was never registered.
Fix: define GantryKeyboardState::get() in libmujoco_ros2_control.so with
visibility("default") so the symbol is exported to the global table. The plugins
DSO now carries only an undefined reference resolved at dlopen time, eliminating
the premature static-constructor problem while preserving the singleton guarantee.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
class_loader loads hardware-interface plugins with RTLD_LOCAL, which keeps
this DSO's symbols (GantryKeyboardState::get) out of the global symbol table.
When VirtualGantryPlugin then calls GantryKeyboardState::get() it gets an
undefined-symbol crash (exit 127).
Use dladdr to find our own DSO path, then dlopen with RTLD_NOLOAD|RTLD_GLOBAL
to promote visibility in-place — no reload, no extra reference count. This
runs before the ClassLoader is created, so plugin factory registration is
unaffected.
Also add ${CMAKE_DL_LIBS} to link libdl for dlopen/dladdr/dlclose.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
d24da5b to
c2d8318
Compare
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
|
Thanks, lgtm overall. See some small comments directly in the code. Additionally I have a bigger comment on the architecture: Currently this PR introduces a I would propose we instead add one virtual to // mujoco_ros2_control_plugins_base.hpp
virtual void on_key(int key, int scancode, int action, int mods) {}// mujoco_system_interface.cpp — replaces the GantryKeyboardState block
for (auto& plugin : plugin_instances_) plugin->on_key(key, scancode, action, mods);
Agent prompt to apply this refactor |
lgulich
left a comment
There was a problem hiding this comment.
Three small inline items alongside the architecture note above.
…, cleanup UAF - Fix '[ ]/]' step comment: 5 cm → 0.5 cm in hpp and mujoco_system_interface.cpp - Fix stale 'Shift+scroll' reference in rope_length_ docstring → '['/']' keys - Fix cleanup() UAF: hold state_mutex_ before resetting enable_srv_ and node_ Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
…d of shared singleton Replace the GantryKeyboardState singleton + RTLD_GLOBAL + dlopen/dladdr/CMAKE_DL_LIBS machinery with a single on_key() virtual on MuJoCoROS2ControlPluginBase. The GLFW adapter now fans out every key event to all loaded plugins; each plugin handles the keys it cares about via its own std::atomic members. - Add on_key() to MuJoCoROS2ControlPluginBase (UI-thread, non-blocking contract) - ROS2ControlGlfwAdapter accepts plugin_instances_ by reference and fans out OnKey - VirtualGantryPlugin overrides on_key(), owns toggle_counter_ and rope_length_ticks_ - Delete gantry_keyboard_state.hpp and gantry_keyboard_state.cpp - Remove CMAKE_DL_LIBS linkage and gantry_keyboard_state.cpp from CMakeLists.txt Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
…uJoCo viewer [ and ] were being forwarded to the parent GlfwAdapter after plugin handling, triggering MuJoCo's native camera-switching binding. on_key now returns true when a key is consumed; the adapter skips mj::GlfwAdapter::OnKey in that case. Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
|
Done in 84766f5. Replaced the GantryKeyboardState singleton + RTLD_GLOBAL + dlopen/dladdr/CMAKE_DL_LIBS block with a |
…etBool Drop mujoco_ros2_control_msgs/srv/SetGantryEnabled (structurally identical to std_srvs/SetBool). Update VirtualGantryPlugin, its deps (CMakeLists, package.xml), and the README service examples (req->enabled -> req->data, type updated). Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
40202a4
into
NVIDIA-ISAAC-ROS:impedence-control-support
Summary
Adds a
VirtualGantryPluginthat suspends a humanoid robot from afixed anchor point using a one-sided cable constraint. Intended as a
safety net during locomotion policy bring-up: the rope catches falls
without constraining normal motion, so the robot can walk and balance
freely.
Physics model
A one-sided spring-damper acting along the radial direction only. When
the straight-line distance from the anchor to the configured attachment
point exceeds
rope_length, a tension force is applied toward theanchor. Because the force is purely radial the robot swings freely like
a pendulum at all times. The damper is applied only when the rope is
extending, preventing the asymmetric energy cycle that bidirectional
damping creates with a one-sided constraint.
On (re-)enable the anchor is placed at
[attach_xy, anchor_z]andrope_lengthis set to|anchor_z − attach_z|so the rope is justtaut at the moment of activation. On simulation reset the gantry
auto-reactivates and re-anchors above the current attachment position.
Controls
G[]ROS 2 service
set_gantry_enabled(mujoco_ros2_control_msgs/srv/SetGantryEnabled) also enables/disables from the command line.Implementation notes
GantryKeyboardStatesingleton: lock-free (std::atomic) struct defined inlibmujoco_ros2_control.soand shared between the GLFW UI thread (ROS2ControlGlfwAdapter::OnKey) and the physics thread (VirtualGantryPlugin::update). The singleton is declared in a new header and its definition lives ingantry_keyboard_state.cppin the main library so there is exactly one instance across DSO boundaries.RTLD_GLOBAL fix:
pluginlibloads hardware-interface plugins withRTLD_LOCAL, which hidesGantryKeyboardState::getfrom the plugin DSO and causes an undefined-symbol crash.MujocoSystemInterface::load_mujoco_pluginsnow callsdlopen(RTLD_NOLOAD | RTLD_GLOBAL)on its own DSO path before theClassLoaderis created, promoting visibility in-place without an extra reference count.Finite-difference derivative with EMA:
rope_dist_dotis computed asd(rope_dist)/dtrather than fromcvelto avoid phase errors when physics runs faster than the control loop. An exponential moving average (τ ≈ 10 ms) filters contact/joint noise from the raw 2 ms finite difference. The derivative state is reset to zero whenever the rope goes slack, preventing stale velocity from spiking the damper at the next taut transition.