CINXE.COM
foam: A Tool for Spherical Approximation of Robot Geometry
<!DOCTYPE html> <html lang="en"> <head> <meta content="text/html; charset=utf-8" http-equiv="content-type"/> <title>foam: A Tool for Spherical Approximation of Robot Geometry</title> <!--Generated on Mon Mar 17 20:18:46 2025 by LaTeXML (version 0.8.8) http://dlmf.nist.gov/LaTeXML/.--> <meta content="width=device-width, initial-scale=1, shrink-to-fit=no" name="viewport"/> <link href="https://cdn.jsdelivr.net/npm/bootstrap@5.3.0/dist/css/bootstrap.min.css" rel="stylesheet" type="text/css"/> <link href="/static/browse/0.3.4/css/ar5iv.0.7.9.min.css" rel="stylesheet" type="text/css"/> <link href="/static/browse/0.3.4/css/ar5iv-fonts.0.7.9.min.css" rel="stylesheet" type="text/css"/> <link href="/static/browse/0.3.4/css/latexml_styles.css" rel="stylesheet" type="text/css"/> <script src="https://cdn.jsdelivr.net/npm/bootstrap@5.3.0/dist/js/bootstrap.bundle.min.js"></script> <script src="https://cdnjs.cloudflare.com/ajax/libs/html2canvas/1.3.3/html2canvas.min.js"></script> <script src="/static/browse/0.3.4/js/addons_new.js"></script> <script src="/static/browse/0.3.4/js/feedbackOverlay.js"></script> <base href="/html/2503.13704v1/"/></head> <body> <nav class="ltx_page_navbar"> <nav class="ltx_TOC"> <ol class="ltx_toclist"> <li class="ltx_tocentry ltx_tocentry_section"><a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S1" title="In foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_title"><span class="ltx_tag ltx_tag_ref">I </span><span class="ltx_text ltx_font_smallcaps">Introduction</span></span></a></li> <li class="ltx_tocentry ltx_tocentry_section"><a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S2" title="In foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_title"><span class="ltx_tag ltx_tag_ref">II </span><span class="ltx_text ltx_font_smallcaps">Related Work</span></span></a></li> <li class="ltx_tocentry ltx_tocentry_section"> <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3" title="In foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_title"><span class="ltx_tag ltx_tag_ref">III </span><span class="ltx_text ltx_font_smallcaps">The Foam Library</span></span></a> <ol class="ltx_toclist ltx_toclist_section"> <li class="ltx_tocentry ltx_tocentry_subsection"><a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.SS1" title="In III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_title"><span class="ltx_tag ltx_tag_ref"><span class="ltx_text">III-A</span> </span><span class="ltx_text ltx_font_italic">URDF Collision Geometry</span></span></a></li> <li class="ltx_tocentry ltx_tocentry_subsection"><a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.SS2" title="In III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_title"><span class="ltx_tag ltx_tag_ref"><span class="ltx_text">III-B</span> </span><span class="ltx_text ltx_font_italic">Mesh Preprocessing</span></span></a></li> <li class="ltx_tocentry ltx_tocentry_subsection"><a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.SS3" title="In III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_title"><span class="ltx_tag ltx_tag_ref"><span class="ltx_text">III-C</span> </span><span class="ltx_text ltx_font_italic">Spherization of Meshes</span></span></a></li> <li class="ltx_tocentry ltx_tocentry_subsection"><a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.SS4" title="In III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_title"><span class="ltx_tag ltx_tag_ref"><span class="ltx_text">III-D</span> </span><span class="ltx_text ltx_font_italic">The Foam Tool</span></span></a></li> </ol> </li> <li class="ltx_tocentry ltx_tocentry_section"><a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S4" title="In foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_title"><span class="ltx_tag ltx_tag_ref">IV </span><span class="ltx_text ltx_font_smallcaps">Empirical Results</span></span></a></li> <li class="ltx_tocentry ltx_tocentry_section"><a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S5" title="In foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_title"><span class="ltx_tag ltx_tag_ref">V </span><span class="ltx_text ltx_font_smallcaps">Discussion</span></span></a></li> </ol></nav> </nav> <div class="ltx_page_main"> <div class="ltx_page_content"> <article class="ltx_document ltx_authors_1line"> <div class="ltx_para" id="p1"> <span class="ltx_ERROR undefined" id="p1.1">\addbibresource</span> <p class="ltx_p" id="p1.2">references.bib </p> </div> <h1 class="ltx_title ltx_font_bold ltx_title_document" style="font-size:173%;"> <span class="ltx_text ltx_font_typewriter ltx_font_medium" id="id1.id1">foam</span>: A Tool for Spherical Approximation of Robot Geometry </h1> <div class="ltx_authors"> <span class="ltx_creator ltx_role_author"> <span class="ltx_personname">Sai Coumar, Gilbert Chang, Nihar Kodkani, and Zachary Kingston </span><span class="ltx_author_notes"> SC, GC, NK, and ZK are with the <a class="ltx_ref ltx_href" href="https://commalab.org/" title="">CoMMA Lab</a>, Department of Computer Science, Purdue University, West Lafayette, IN, USA <br class="ltx_break"/><span class="ltx_text ltx_font_typewriter" id="id2.1.id1">{scoumar, chang940, nkodkani, zkingston}@purdue.edu</span></span></span> </div> <div class="ltx_abstract"> <h6 class="ltx_title ltx_title_abstract">Abstract</h6> <p class="ltx_p" id="id3.id1">Many applications in robotics require primitive spherical geometry, especially in cases where efficient distance queries are necessary. Manual creation of spherical models is time-consuming and prone to errors. This paper presents <span class="ltx_text ltx_font_typewriter" id="id3.id1.1">foam</span>, a tool to generate spherical approximations of robot geometry from an input Universal Robot Description Format (URDF) file. <span class="ltx_text ltx_font_typewriter" id="id3.id1.2">foam</span> provides a robust preprocessing pipeline to handle mesh defects and a number of configuration parameters to control the level and approximation of the spherization, and generates an output URDF with collision geometry specified only by spheres. We demonstrate <span class="ltx_text ltx_font_typewriter" id="id3.id1.3">foam</span> on a number of standard robot models on common tasks, and demonstrate improved collision checking and distance query performance with only a minor loss in fidelity compared to the true collision geometry. We release our tool as an open source Python library and containerized command-line application to facilitate adoption across the robotics community.</p> </div> <section class="ltx_section" id="S1"> <h2 class="ltx_title ltx_title_section"> <span class="ltx_tag ltx_tag_section">I </span><span class="ltx_text ltx_font_smallcaps" id="S1.1.1">Introduction</span> </h2> <div class="ltx_para" id="S1.p1"> <p class="ltx_p" id="S1.p1.1">Efficient collision detection (both as binary classification and measuring distance to collision) is a fundamental challenge throughout robotics; algorithms and control strategies from real-time model-predictive control <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">chiu2022collision</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">gaertner2021collision</span>]</cite>, sampling-based motion planning <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">sundaralingam2023curobo</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">thomason2024motions</span>]</cite>, simulation <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">Coumans2016</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">todorov2012mujoco</span>]</cite>, and more all rely on effective collision detection of the robot’s geometry with that of the environments. Although effective collision detection strategies exist for complex geometries (e.g., space decompositions, parallel approaches, GPU-accelerated algorithms), these approaches scale on the complexity of the involved geometry, and performance improves when the representative geometry of the robot and environment is simple.</p> </div> <div class="ltx_para" id="S1.p2"> <p class="ltx_p" id="S1.p2.1">Moreover, many robot descriptions (usually in URDF) are exported from CAD tools <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">tola2024understanding</span>]</cite>, which may contain extraneous details for coarse collision checking. These complex meshes also often contain non-manifold geometry (that is, non-watertight) and may contain geometry that violates assumptions made by geometric processing pipelines, e.g., flat planes or single faces. A common approach is to provide simplified geometry to represent the collision geometry of the robot, either with a set of convex meshes <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">schulman2014motion</span>]</cite> or with a set of primitives <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">zucker2013chomp</span>]</cite>. This is advantageous as collision checking with primitive approximations is more efficient for collision checking and signed distance queries (e.g., as in <span class="ltx_ERROR undefined" id="S1.p2.1.1">\citet</span>mukadam2018continuous,sundaralingam2023curobo), which are prevalent in modern robotics applications. However, although these primitive approximations are useful and widely used, existing tools lack robust automation for converting existing robot geometry into these primitive decompositions.</p> </div> <figure class="ltx_figure" id="S1.F1"> <table class="ltx_tabular ltx_centering ltx_align_middle" id="S1.F1.1"> <tbody class="ltx_tbody"> <tr class="ltx_tr" id="S1.F1.1.1"> <td class="ltx_td ltx_align_center" id="S1.F1.1.1.1" style="padding-top:1.5pt;padding-bottom:1.5pt;"><img alt="Refer to caption" class="ltx_graphics ltx_img_square" height="720" id="S1.F1.1.1.1.g1" src="extracted/6288087/images/menagerie.png" width="598"/></td> </tr> </tbody> </table> <figcaption class="ltx_caption ltx_centering"><span class="ltx_tag ltx_tag_figure">Figure 1: </span>Results of spherizing commonly used robots with <span class="ltx_text ltx_font_typewriter" id="S1.F1.4.1">foam</span>. From left to right: Franka Emika Panda, KUKA IIWA, and Kinova Jaco robots (top row), alongside spherized approximations (middle and bottom row). Displayed are spherizations of the Panda with 22 and 28 spheres, the IIWA with 13 and 19 spheres, and the Kinova with 22 and 39 spheres. Our <span class="ltx_text ltx_font_typewriter" id="S1.F1.5.2">foam</span> library automatically processes robots specified with a URDF and creates a URDF with spherical approximations of the robot’s collision geometry.</figcaption> </figure> <div class="ltx_para" id="S1.p3"> <p class="ltx_p" id="S1.p3.1">This paper presents <span class="ltx_text ltx_font_typewriter" id="S1.p3.1.1">foam</span>, an automated framework for generating spherical approximations of robot geometries directly from Universal Robot Description Format (URDF) specifications. The <span class="ltx_text ltx_font_typewriter" id="S1.p3.1.2">foam</span> spherization pipeline balances geometric accuracy with computational efficiency through a number of configurable approximation parameters, building upon existing work on the medial sphere-tree approximation for meshes <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">bradshaw2004adaptive</span>]</cite>. Our preprocessing pipeline handles and fixes common mesh defects gracefully, while maintaining critical geometric features needed for collision detection. The output of <span class="ltx_text ltx_font_typewriter" id="S1.p3.1.3">foam</span> is an equivalent URDF of the input robot, but with all collision geometry replaced by spheres. We evaluated the output URDFs of <span class="ltx_text ltx_font_typewriter" id="S1.p3.1.4">foam</span> across multiple standard robots and applications, and we demonstrated that <span class="ltx_text ltx_font_typewriter" id="S1.p3.1.5">foam</span>-generated models achieve collision checking performance improvements while maintaining geometric fidelity suitable for practical robotic tasks. To the authors’ knowledge, while spherization tools for just meshes exist open source, nothing has been packaged as a convenient tool for roboticists; we release our tool as open source at <a class="ltx_ref ltx_url ltx_font_typewriter" href="https://github.com/CoMMALab/foam/" title="">https://github.com/CoMMALab/foam/</a> as a Python library and containerized command-line tool.</p> </div> </section> <section class="ltx_section" id="S2"> <h2 class="ltx_title ltx_title_section"> <span class="ltx_tag ltx_tag_section">II </span><span class="ltx_text ltx_font_smallcaps" id="S2.1.1">Related Work</span> </h2> <div class="ltx_para" id="S2.p1"> <p class="ltx_p" id="S2.p1.1"><span class="ltx_text ltx_font_typewriter" id="S2.p1.1.1">foam</span> focuses on generating the spherical decomposition of a given robot geometry. Sphere-based modeling of robots has become increasingly prominent, as spherical approximations facilitate both efficient collision checking and efficient computation of Euclidean distance transforms (EDTs) <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">felzenszwalb2012distance</span>]</cite> and signed distance fields (SDFs) <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">ye1988signed</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">oleynikova2016signed</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">ortiz2022isdf</span>]</cite> with respect to a robot’s current configuration, which are both essential for many gradient-based and cost-map methods in robotics. For example, in motion planning alone, trajectory optimization approaches such as CHOMP <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">zucker2013chomp</span>]</cite>, STOMP <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">kalakrishnan2011stomp</span>]</cite>, motion planning as inference methods such as GPMP2 <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">dong2016motion</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">mukadam2018continuous</span>]</cite>, and cuRobo <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">sundaralingam2023curobo</span>]</cite> all rely on spherical models for SDF computation. The recently proposed SIMD-accelerated sampling-based planning methods in <span class="ltx_ERROR undefined" id="S2.p1.1.2">\citet</span>thomason2024motions also rely on spherical decompositions of the robot’s geometry for efficient collision detection.</p> </div> <div class="ltx_para" id="S2.p2"> <p class="ltx_p" id="S2.p2.1">Our tool is built upon existing methods for automatic approximation of a mesh by a set of spheres. Early approaches used simple voxelizations (which are still used in, e.g., <span class="ltx_ERROR undefined" id="S2.p2.1.1">\citet</span>sundaralingam2023curobo) or octree decompositions <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">hubbard1993interactive</span>]</cite>. Other tools fit spheres along the medial axis of the geometry <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">hubbard1996approximating</span>]</cite>, that is, along the set of points inside the mesh having more than one closest point on the mesh’s boundary. For robots with simple collision geometry, e.g., cylinders, this is simple and can be done analytically, as done by <span class="ltx_ERROR undefined" id="S2.p2.1.2">\citet</span>volz2018computation. <span class="ltx_text ltx_font_typewriter" id="S2.p2.1.3">foam</span> is built on top of an improvement to these medial axis approaches, the Adaptive Medial Axis Approximation (AMAA) method of <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">bradshaw2004adaptive</span>]</cite>. Although subsequent approaches have refined the AMAA approach (e.g., <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">wang2006variational</span>]</cite>), open source code was not available to build on. Sphere decompositions have also been used in discrete element models for particle simulations <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">angelidakis2021clump</span>]</cite>.</p> </div> <div class="ltx_para" id="S2.p3"> <p class="ltx_p" id="S2.p3.1">Given the impact of mesh complexity on the performance of collision checking, rendering, and other geometric algorithms <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">rtcd</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">kockara2007collision</span>]</cite>, there has been much research on a variety of decomposition, simplification, and approximation methods for the processing of geometry. While alternative primitive representations have been explored in the literature, such as cuboid decompositions <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">sun2019learning</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">yang2021unsupervised</span>]</cite> and quadric-based models <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">thiery2013sphere</span>]</cite>, these have seen less adoption due to their complexity and lack of benefit for computing SDF and EDT functions. Convex decomposition methods, e.g., V-HACD <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">mamou2009simple</span>]</cite> and CoACD <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">wei2022approximate</span>]</cite>, decompose a non-convex mesh into a set of convex meshes that approximate the original. Highlighting the importance of geometry preprocessing, these decomposition techniques are critical not only for efficient geometric representation, but also for modern dataset curation. This is evidenced by recent works that incorporate CoACD into large-scale robotics datasets <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">gu2023maniskill2</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">wang2023dexgraspnet</span>]</cite>. There are also other mesh simplification and low-poly approximation pipelines <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">cohen1996simplification</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">garland1997surface</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">calderon2017bounding</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">chen2023robust</span>]</cite> that reduce the number of vertices in a mesh, but do not change the mesh into convex or primitive geometry.</p> </div> </section> <section class="ltx_section" id="S3"> <h2 class="ltx_title ltx_title_section"> <span class="ltx_tag ltx_tag_section">III </span><span class="ltx_text ltx_font_smallcaps" id="S3.1.1">The Foam Library</span> </h2> <div class="ltx_para" id="S3.p1"> <p class="ltx_p" id="S3.p1.1">The <span class="ltx_text ltx_font_typewriter" id="S3.p1.1.1">foam</span> Library provides an automated framework for creating spherical approximations of robot geometries directly from Universal Robot Description Format (URDF) specifications. By converting complex polygonal meshes into simplified sphere-based representations, <span class="ltx_text ltx_font_typewriter" id="S3.p1.1.2">foam</span> significantly improves computational efficiency for collision detection while maintaining sufficient geometric fidelity for practical robotics applications. The library offers a configurable pipeline that handles common mesh defects gracefully, preserves critical geometric features, and outputs equivalent URDFs with collision geometry replaced by spheres.</p> </div> <section class="ltx_subsection" id="S3.SS1"> <h3 class="ltx_title ltx_title_subsection"> <span class="ltx_tag ltx_tag_subsection"><span class="ltx_text" id="S3.SS1.5.1.1">III-A</span> </span><span class="ltx_text ltx_font_italic" id="S3.SS1.6.2">URDF Collision Geometry</span> </h3> <div class="ltx_para" id="S3.SS1.p1"> <p class="ltx_p" id="S3.SS1.p1.1">In a robot’s URDF, the collision geometry is specified by some number of <span class="ltx_text ltx_font_typewriter" id="S3.SS1.p1.1.1"><collision/></span> tags in each of the robot’s <span class="ltx_text ltx_font_typewriter" id="S3.SS1.p1.1.2"><link/></span> tags. These can either be primitives (e.g., spheres, cuboids, cylinders), or by most of the time referencing external mesh files that are composed of complex polygons. Some robot manufacturers provide convex hulls, simplified mesh geometry, or primitive approximations for collision checking, but many are simply raw CAD file output <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">tola2024understanding</span>]</cite>; in some cases the details are potentially so fine that screw holes are captured in the geometry.</p> </div> <div class="ltx_para" id="S3.SS1.p2"> <p class="ltx_p" id="S3.SS1.p2.1"><span class="ltx_text ltx_font_typewriter" id="S3.SS1.p2.1.1">foam</span> creates simple, accurate spherized approximations of the geometries within a robot’s URDF, either specified as meshes or as primitives. Our tool can either output spheres in a JSON database or in standard URDF representation (that is, a copy of the original robot’s URDF with all the collision geometry replaced by a set of sphere primitives). The <span class="ltx_text ltx_font_typewriter" id="S3.SS1.p2.1.2">foam</span> library provides some utility functions to load URDFs, retrieve all mesh files used in a URDF, modify a URDF to include spheres, and save the output file, respectively <span class="ltx_text ltx_font_typewriter ltx_font_bold" id="S3.SS1.p2.1.3">load_urdf(), get_urdf_meshes(), set_urdf_spheres()</span> and <span class="ltx_text ltx_font_typewriter ltx_font_bold" id="S3.SS1.p2.1.4">save_urdf()</span>.</p> </div> <div class="ltx_para" id="S3.SS1.p3"> <p class="ltx_p" id="S3.SS1.p3.1">We note that our simplified spherized models can be easily utilized in simulators such as MuJoCo <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">todorov2012mujoco</span>]</cite>, and spherization removes the dependency on external mesh assets. Generated spheres can be used in other applications that may benefit from simplified spherical approximations. For example, Pinocchio, which uses FCL collision checking, benefits greatly from mesh simplification due to using a collision library that is optimized for simplified geometry <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">carpentier2019pinocchio</span>, <span class="ltx_ref ltx_missing_citation ltx_ref_self">fcl</span>]</cite>.</p> </div> </section> <section class="ltx_subsection" id="S3.SS2"> <h3 class="ltx_title ltx_title_subsection"> <span class="ltx_tag ltx_tag_subsection"><span class="ltx_text" id="S3.SS2.5.1.1">III-B</span> </span><span class="ltx_text ltx_font_italic" id="S3.SS2.6.2">Mesh Preprocessing</span> </h3> <figure class="ltx_figure" id="S3.F2"><img alt="Refer to caption" class="ltx_graphics ltx_centering ltx_img_landscape" height="85" id="S3.F2.g1" src="extracted/6288087/images/pipeline_w_curobo.png" width="598"/> <figcaption class="ltx_caption ltx_centering"><span class="ltx_tag ltx_tag_figure">Figure 2: </span>A representative example of a mesh being processed by <span class="ltx_text ltx_font_typewriter" id="S3.F2.11.1">foam</span>. Here, the 6th link of the Franka Emika Panda <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">haddadin2024franka</span>]</cite> is processed into a set of spheres. From left to right: <span class="ltx_text ltx_font_bold" id="S3.F2.12.2">(1)</span> the original mesh is made into a <span class="ltx_text ltx_font_bold" id="S3.F2.13.3">(2)</span> guaranteed <em class="ltx_emph ltx_font_italic" id="S3.F2.14.4">watertight</em> or <em class="ltx_emph ltx_font_italic" id="S3.F2.15.5">manifold</em> mesh through <span class="ltx_ERROR undefined" id="S3.F2.16.6">\citet</span>huang2018robust. The watertight mesh is then simplified <span class="ltx_text ltx_font_bold" id="S3.F2.17.7">(3)</span> using a quadric-based edge collapse mesh simplification method <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">garland1997surface</span>]</cite> and smoothed <span class="ltx_text ltx_font_bold" id="S3.F2.18.8">(4)</span> with Laplacian smoothing and Humphrey filtering <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">vollmer1999improved</span>]</cite>. Finally, spheres are fit to the processed mesh <span class="ltx_text ltx_font_bold" id="S3.F2.19.9">(5)</span> with adaptive medial axis approximation method <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">bradshaw2004adaptive</span>]</cite>. We also show the <span class="ltx_text ltx_font_bold" id="S3.F2.20.10">(6)</span> spherization approach provided in cuRobo <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">sundaralingam2023curobo</span>]</cite>, which voxelizes the mesh into spheres with a given sphere radius. From left to right, we show decompositions with 200 spheres and 2cm radius, 500 spheres and 1cm radius, 1000 spheres and 1cm radius</figcaption> </figure> <div class="ltx_para" id="S3.SS2.p1"> <p class="ltx_p" id="S3.SS2.p1.1">Many polygonal mesh processing algorithms (including our desired spherization approach) assume that the input mesh is <em class="ltx_emph ltx_font_italic" id="S3.SS2.p1.1.1">watertight</em> or <em class="ltx_emph ltx_font_italic" id="S3.SS2.p1.1.2">manifold</em> (specifically a 2-manifold). As implied by the name, a watertight mesh is such that it can “hold water”, that is, it does not have holes or other broken geometry, e.g., edges with more than two incident faces, mesh faces intersecting each other, faces that are not connected together, etc. Watertight meshes also have a clear definition of the interior and exterior of the mesh. Unfortunately, many URDFs contain robot geometry that has been exported from automated tools <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">tola2024understanding</span>]</cite>, and therefore may contain multiple defects. These defects are also common among many meshes used in everyday tools, e.g., it is known that many of the meshes in ShapeNet <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">chang2015shapenet</span>]</cite> are non-manifold. Moreover, for our downstream tasks of collision checking and spherization, these meshes may have extraneous detail that adds additional complexity to the mesh which is unessential.</p> </div> <div class="ltx_para" id="S3.SS2.p2"> <p class="ltx_p" id="S3.SS2.p2.1">In order to handle non-watertight meshes, <span class="ltx_text ltx_font_typewriter" id="S3.SS2.p2.1.1">foam</span> uses a preprocessing pipeline to handle these defects while preserving essential geometric features required for collision detection. This preprocessing pipeline also reduces the complexity of the mesh, improving the performance of the final spherization algorithm. A representative output from each stage of the pipeline is shown in <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F2" title="In III-B Mesh Preprocessing ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">2</span></a>. Each of these steps has a number of configurable hyperparameters to control the amount of simplification, smoothing, and processing the input mesh goes through.</p> </div> <div class="ltx_para" id="S3.SS2.p3"> <p class="ltx_p" id="S3.SS2.p3.1">The preprocessing workflow begins after the collision meshes are loaded with Trimesh <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">trimesh</span>]</cite> (<a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F2" title="In III-B Mesh Preprocessing ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">2</span></a>-1). The mesh is then transformed into a guaranteed watertight mesh using the method of <span class="ltx_ERROR undefined" id="S3.SS2.p3.1.1">\citet</span>huang2018robust (<a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F2" title="In III-B Mesh Preprocessing ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">2</span></a>-2). This step is crucial and ensures topological consistency by eliminating non-manifold edges, dangling faces, and small holes that could otherwise compromise the accuracy of subsequent spherization. Following this step, we then simplify the manifold mesh with a quadric-based edge collapse simplification method <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">garland1997surface</span>]</cite> to reduce complexity, as downstream algorithms scale with the number of triangles in the mesh and are more robust with less complex input (e.g., see <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F3" title="In III-B Mesh Preprocessing ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">3</span></a>). This produces a simplified mesh (<a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F2" title="In III-B Mesh Preprocessing ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">2</span></a>-3) with significantly fewer vertices and faces, yet preserves the essential shape characteristics of the original geometry. The process continues with a smoothing phase (<a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F2" title="In III-B Mesh Preprocessing ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">2</span></a>-4) that applies both Laplacian smoothing and Humphrey filtering <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">vollmer1999improved</span>]</cite> (<span class="ltx_text ltx_font_typewriter ltx_font_bold" id="S3.SS2.p3.1.2">smooth_manifold()</span> in the <span class="ltx_text ltx_font_typewriter" id="S3.SS2.p3.1.3">foam</span> library) to remove small-scale irregularities and noise from the mesh surface, creating a more uniform geometric representation suitable for sphere fitting.</p> </div> <figure class="ltx_figure" id="S3.F3"><img alt="Refer to caption" class="ltx_graphics ltx_centering ltx_img_landscape" height="299" id="S3.F3.g1" src="extracted/6288087/images/spherization_time/spherization_times.png" width="598"/> <figcaption class="ltx_caption ltx_centering"><span class="ltx_tag ltx_tag_figure">Figure 3: </span>Time to spherize an input mesh against the number of triangles in the input mesh.</figcaption> </figure> </section> <section class="ltx_subsection" id="S3.SS3"> <h3 class="ltx_title ltx_title_subsection"> <span class="ltx_tag ltx_tag_subsection"><span class="ltx_text" id="S3.SS3.5.1.1">III-C</span> </span><span class="ltx_text ltx_font_italic" id="S3.SS3.6.2">Spherization of Meshes</span> </h3> <figure class="ltx_figure" id="S3.F4"><img alt="Refer to caption" class="ltx_graphics ltx_centering ltx_img_landscape" height="91" id="S3.F4.g1" src="extracted/6288087/images/banner_varying_res.png" width="598"/> <figcaption class="ltx_caption ltx_centering"><span class="ltx_tag ltx_tag_figure">Figure 4: </span>Franka Emika Panda Robot <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">haddadin2024franka</span>]</cite> processed with <span class="ltx_text ltx_font_typewriter" id="S3.F4.11.1">foam</span> to generate spherized models with increasing level of fidelity, with (left to right) <span class="ltx_text ltx_font_bold" id="S3.F4.12.2">(1)</span> 11, <span class="ltx_text ltx_font_bold" id="S3.F4.13.3">(2)</span> 22, <span class="ltx_text ltx_font_bold" id="S3.F4.14.4">(3)</span> 27, <span class="ltx_text ltx_font_bold" id="S3.F4.15.5">(4)</span> 92, and <span class="ltx_text ltx_font_bold" id="S3.F4.16.6">(5)</span> 316 spheres. The spheres on the robot are colored by size, indicated by the colorbar on the far right. We compare the output of <span class="ltx_text ltx_font_typewriter" id="S3.F4.17.7">foam</span> to <span class="ltx_text ltx_font_bold" id="S3.F4.18.8">(6)</span> a custom-made spherization of the Panda from <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">fishman2023motion</span>]</cite> with 59 spheres, which is a clear under-approximation of the robot’s <span class="ltx_text ltx_font_bold" id="S3.F4.19.9">(7)</span> true collision geometry. We also display <span class="ltx_text ltx_font_bold" id="S3.F4.20.10">(8)</span>, the robot’s visual geometry, as reference.</figcaption> </figure> <div class="ltx_para" id="S3.SS3.p1"> <p class="ltx_p" id="S3.SS3.p1.1">After the mesh has been processed into a simplified, watertight mesh, it is then spherized with an implementation of the Adaptive Medial Axis Approximation (AMAA) algorithm of <span class="ltx_ERROR undefined" id="S3.SS3.p1.1.1">\citet</span>bradshaw2004adaptive (<span class="ltx_text ltx_font_typewriter ltx_font_bold" id="S3.SS3.p1.1.2">spherize_mesh</span> using the <span class="ltx_text ltx_font_typewriter ltx_font_bold" id="S3.SS3.p1.1.3">medial</span> option in the <span class="ltx_text ltx_font_typewriter" id="S3.SS3.p1.1.4">foam</span> library). An output from the AMAA processing can be seen in <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F2" title="In III-B Mesh Preprocessing ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">2</span></a>-5, which shows how the mesh can be effectively covered with only 9 spheres. We contrast the output of AMAA after our preprocessing to the provided spherization tool in cuRobo <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">sundaralingam2023curobo</span>]</cite>, where a variety of outputs are shown in <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F2" title="In III-B Mesh Preprocessing ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">2</span></a>-6. Their approach performs a simplified voxelization of the mesh into spheres with a given sphere radius.</p> </div> <div class="ltx_para" id="S3.SS3.p2"> <p class="ltx_p" id="S3.SS3.p2.1">We also expose other methods for spherization (e.g., a voxel grid-based decomposition with <span class="ltx_text ltx_font_typewriter ltx_font_bold" id="S3.SS3.p2.1.1">grid</span>), but these notably provide less high-fidelity spherizations There are also a number of keyword arguments to control the spherization process—a number of them are listed in the example code in <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F5" title="In III-D The Foam Tool ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">5</span></a> (e.g., the maximum number of desired spheres can be specified with the <span class="ltx_text ltx_font_typewriter ltx_font_bold" id="S3.SS3.p2.1.2">branch</span> parameter). This control of the amount of desired spherization is illustrated in <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F4" title="In III-C Spherization of Meshes ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">4</span></a>, which shows the Franka Emika Panda robot spherized with increasing amounts of spheres. This allows users to control the fidelity and complexity of the output spherized model, either remaining coarse or reaching a close-fitting approximation. We contrast the output of <span class="ltx_text ltx_font_typewriter" id="S3.SS3.p2.1.3">foam</span> (<a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F4" title="In III-C Spherization of Meshes ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">4</span></a>-1–5) with a custom-made spherization from <span class="ltx_ERROR undefined" id="S3.SS3.p2.1.4">\citet</span>fishman2023motion (<a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F4" title="In III-C Spherization of Meshes ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">4</span></a>-6). <span class="ltx_text ltx_font_typewriter" id="S3.SS3.p2.1.5">foam</span>’s spherization more closely matches the true robot collision geometry (<a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F4" title="In III-C Spherization of Meshes ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">4</span></a>-7) and is a conservative overapproximation, rather than an underapproximation.</p> </div> </section> <section class="ltx_subsection" id="S3.SS4"> <h3 class="ltx_title ltx_title_subsection"> <span class="ltx_tag ltx_tag_subsection"><span class="ltx_text" id="S3.SS4.5.1.1">III-D</span> </span><span class="ltx_text ltx_font_italic" id="S3.SS4.6.2">The Foam Tool</span> </h3> <figure class="ltx_figure" id="S3.F5"> <div class="ltx_listing ltx_lst_language_Python ltx_lst_numbers_left ltx_lstlisting ltx_listing" id="S3.F5.1" style="border-color: #6D6D6D;"> <div class="ltx_listing_data"><a download="" href="data:text/plain;base64,ZGVmIG1haW4obWVzaDogc3RyLCBvdXRwdXQ6IHN0cik6CiAgICBtZXNoX2ZpbGVwYXRoID0gUGF0aChtZXNoKQogICAgIyBrd2FyZ3MgZm9yIHNwaGVyaXphdGlvbgogICAgc3BoZXJlX2t3YXJncyA9IHsKICAgICAgICAnZGVwdGgnOiAxLAogICAgICAgICdicmFuY2gnOiA4LAogICAgICAgICdtZXRob2QnOiBtZWRpYWwsCiAgICAgICAgJ3Rlc3RlckxldmVscyc6IDIsCiAgICAgICAgJ251bUNvdmVyJzogNTAwLAogICAgICAgICdtaW5Db3Zlcic6IDUsCiAgICAgICAgJ2luaXRTcGhlcmVzJzogMTAwMCwKICAgICAgICAnbWluU3BoZXJlcyc6IDIwMCwKICAgICAgICAnZXJGYWN0JzogMiwKICAgICAgICAnZXhwYW5kJzogVHJ1ZSwKICAgICAgICAnbWVyZ2UnOiBUcnVlLAogICAgICAgICdidXJzdCc6IEZhbHNlLAogICAgICAgICdvcHRpbWlzZSc6IFRydWUsCiAgICAgICAgJ21heE9wdExldmVsJzogMSwKICAgICAgICAnYmFsRXhjZXNzJzogMC4wNSwKICAgICAgICAndmVyaWZ5JzogVHJ1ZSwKICAgICAgICAnbnVtX3NhbXBsZXMnOiA1MDAsCiAgICAgICAgJ21pbl9zYW1wbGVzJzogMQogICAgfQogICAgIyBrd2FyZ3MgZm9yIG1lc2ggcHJvY2Vzc2luZwogICAgcHJvY2Vzc19rd2FyZ3MgPSB7CiAgICAgICAgJ21hbmlmb2xkX2xlYXZlcyc6IDEwMDAsCiAgICAgICAgJ3JhdGlvJzogMC4yLAogICAgfQogICAgIyBDYWxsIHNwaGVyaXplX21lc2ggd2l0aCBrd2FyZ3MKICAgIHNwaGVyZXMgPSBzcGhlcml6ZV9tZXNoKAogICAgICAgIG1lc2hfZmlsZXBhdGgsCiAgICAgICAgc3BoZXJpemF0aW9uX2t3YXJncz1zcGhlcmVfa3dhcmdzLAogICAgICAgIHByb2Nlc3Nfa3dhcmdzPXByb2Nlc3Nfa3dhcmdzCiAgICApCiAgICAjIFdyaXRlIHRoZSByZXN1bHQgdG8gYSBKU09OIGZpbGUKICAgIG91dHB1dCA9IG1lc2hfZmlsZXBhdGguc3RlbSArICItc3BoZXJlcyIKICAgIHdpdGggb3BlbihvdXRwdXQgKyAiLmpzb24iLCAndycpIGFzIGY6CiAgICAgICAgZi53cml0ZShkdW1wcyhzcGhlcmVzLCBpbmRlbnQ9NCwgY2xzPVNwaGVyZUVuY29kZXIpKQ==">⬇</a></div> <div class="ltx_listingline" id="lstnumberx1"> <span class="ltx_tag ltx_tag_listingline">1</span><span class="ltx_text ltx_lst_keyword ltx_font_typewriter ltx_font_bold" id="lstnumberx1.1" style="font-size:80%;color:#417598;">def</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx1.2" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx1.3" style="font-size:80%;">main</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx1.4" style="font-size:80%;">(</span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx1.5" style="font-size:80%;">mesh</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx1.6" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx1.7" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_keyword ltx_lst_keywords2 ltx_font_typewriter ltx_font_bold" id="lstnumberx1.8" style="font-size:80%;color:#417598;">str</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx1.9" style="font-size:80%;">,</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx1.10" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx1.11" style="font-size:80%;">output</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx1.12" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx1.13" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_keyword ltx_lst_keywords2 ltx_font_typewriter ltx_font_bold" id="lstnumberx1.14" style="font-size:80%;color:#417598;">str</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx1.15" style="font-size:80%;">):</span> </div> <div class="ltx_listingline" id="lstnumberx2"> <span class="ltx_tag ltx_tag_listingline">2</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx2.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx2.2" style="font-size:80%;">mesh_filepath</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx2.3" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx2.4" style="font-size:80%;">=</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx2.5" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx2.6" style="font-size:80%;">Path</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx2.7" style="font-size:80%;">(</span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx2.8" style="font-size:80%;">mesh</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx2.9" style="font-size:80%;">)</span> </div> <div class="ltx_listingline" id="lstnumberx3"> <span class="ltx_tag ltx_tag_listingline">3</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx3.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_comment ltx_font_typewriter ltx_font_bold" id="lstnumberx3.2" style="font-size:80%;color:#6D6D6D;">#<span class="ltx_text ltx_lst_space" id="lstnumberx3.2.1"> </span>kwargs<span class="ltx_text ltx_lst_space" id="lstnumberx3.2.2"> </span>for<span class="ltx_text ltx_lst_space" id="lstnumberx3.2.3"> </span>spherization</span> </div> <div class="ltx_listingline" id="lstnumberx4"> <span class="ltx_tag ltx_tag_listingline">4</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx4.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx4.2" style="font-size:80%;">sphere_kwargs</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx4.3" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx4.4" style="font-size:80%;">=</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx4.5" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx4.6" style="font-size:80%;">{</span> </div> <div class="ltx_listingline" id="lstnumberx5"> <span class="ltx_tag ltx_tag_listingline">5</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx5.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx5.2" style="font-size:80%;color:#D15120;">’depth’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx5.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx5.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx5.5" style="font-size:80%;">1,</span> </div> <div class="ltx_listingline" id="lstnumberx6"> <span class="ltx_tag ltx_tag_listingline">6</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx6.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx6.2" style="font-size:80%;color:#D15120;">’branch’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx6.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx6.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx6.5" style="font-size:80%;">8,</span> </div> <div class="ltx_listingline" id="lstnumberx7"> <span class="ltx_tag ltx_tag_listingline">7</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx7.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx7.2" style="font-size:80%;color:#D15120;">’method’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx7.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx7.4" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx7.5" style="font-size:80%;">medial</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx7.6" style="font-size:80%;">,</span> </div> <div class="ltx_listingline" id="lstnumberx8"> <span class="ltx_tag ltx_tag_listingline">8</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx8.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx8.2" style="font-size:80%;color:#D15120;">’testerLevels’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx8.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx8.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx8.5" style="font-size:80%;">2,</span> </div> <div class="ltx_listingline" id="lstnumberx9"> <span class="ltx_tag ltx_tag_listingline">9</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx9.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx9.2" style="font-size:80%;color:#D15120;">’numCover’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx9.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx9.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx9.5" style="font-size:80%;">500,</span> </div> <div class="ltx_listingline" id="lstnumberx10"> <span class="ltx_tag ltx_tag_listingline">10</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx10.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx10.2" style="font-size:80%;color:#D15120;">’minCover’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx10.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx10.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx10.5" style="font-size:80%;">5,</span> </div> <div class="ltx_listingline" id="lstnumberx11"> <span class="ltx_tag ltx_tag_listingline">11</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx11.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx11.2" style="font-size:80%;color:#D15120;">’initSpheres’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx11.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx11.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx11.5" style="font-size:80%;">1000,</span> </div> <div class="ltx_listingline" id="lstnumberx12"> <span class="ltx_tag ltx_tag_listingline">12</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx12.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx12.2" style="font-size:80%;color:#D15120;">’minSpheres’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx12.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx12.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx12.5" style="font-size:80%;">200,</span> </div> <div class="ltx_listingline" id="lstnumberx13"> <span class="ltx_tag ltx_tag_listingline">13</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx13.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx13.2" style="font-size:80%;color:#D15120;">’erFact’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx13.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx13.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx13.5" style="font-size:80%;">2,</span> </div> <div class="ltx_listingline" id="lstnumberx14"> <span class="ltx_tag ltx_tag_listingline">14</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx14.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx14.2" style="font-size:80%;color:#D15120;">’expand’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx14.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx14.4" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx14.5" style="font-size:80%;">True</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx14.6" style="font-size:80%;">,</span> </div> <div class="ltx_listingline" id="lstnumberx15"> <span class="ltx_tag ltx_tag_listingline">15</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx15.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx15.2" style="font-size:80%;color:#D15120;">’merge’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx15.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx15.4" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx15.5" style="font-size:80%;">True</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx15.6" style="font-size:80%;">,</span> </div> <div class="ltx_listingline" id="lstnumberx16"> <span class="ltx_tag ltx_tag_listingline">16</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx16.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx16.2" style="font-size:80%;color:#D15120;">’burst’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx16.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx16.4" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx16.5" style="font-size:80%;">False</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx16.6" style="font-size:80%;">,</span> </div> <div class="ltx_listingline" id="lstnumberx17"> <span class="ltx_tag ltx_tag_listingline">17</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx17.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx17.2" style="font-size:80%;color:#D15120;">’optimise’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx17.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx17.4" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx17.5" style="font-size:80%;">True</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx17.6" style="font-size:80%;">,</span> </div> <div class="ltx_listingline" id="lstnumberx18"> <span class="ltx_tag ltx_tag_listingline">18</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx18.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx18.2" style="font-size:80%;color:#D15120;">’maxOptLevel’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx18.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx18.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx18.5" style="font-size:80%;">1,</span> </div> <div class="ltx_listingline" id="lstnumberx19"> <span class="ltx_tag ltx_tag_listingline">19</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx19.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx19.2" style="font-size:80%;color:#D15120;">’balExcess’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx19.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx19.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx19.5" style="font-size:80%;">0.05,</span> </div> <div class="ltx_listingline" id="lstnumberx20"> <span class="ltx_tag ltx_tag_listingline">20</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx20.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx20.2" style="font-size:80%;color:#D15120;">’verify’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx20.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx20.4" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx20.5" style="font-size:80%;">True</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx20.6" style="font-size:80%;">,</span> </div> <div class="ltx_listingline" id="lstnumberx21"> <span class="ltx_tag ltx_tag_listingline">21</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx21.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx21.2" style="font-size:80%;color:#D15120;">’num_samples’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx21.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx21.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx21.5" style="font-size:80%;">500,</span> </div> <div class="ltx_listingline" id="lstnumberx22"> <span class="ltx_tag ltx_tag_listingline">22</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx22.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx22.2" style="font-size:80%;color:#D15120;">’min_samples’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx22.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx22.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx22.5" style="font-size:80%;">1</span> </div> <div class="ltx_listingline" id="lstnumberx23"> <span class="ltx_tag ltx_tag_listingline">23</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx23.1" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx23.2" style="font-size:80%;">}</span> </div> <div class="ltx_listingline" id="lstnumberx24"> <span class="ltx_tag ltx_tag_listingline">24</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx24.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_comment ltx_font_typewriter ltx_font_bold" id="lstnumberx24.2" style="font-size:80%;color:#6D6D6D;">#<span class="ltx_text ltx_lst_space" id="lstnumberx24.2.1"> </span>kwargs<span class="ltx_text ltx_lst_space" id="lstnumberx24.2.2"> </span>for<span class="ltx_text ltx_lst_space" id="lstnumberx24.2.3"> </span>mesh<span class="ltx_text ltx_lst_space" id="lstnumberx24.2.4"> </span>processing</span> </div> <div class="ltx_listingline" id="lstnumberx25"> <span class="ltx_tag ltx_tag_listingline">25</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx25.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx25.2" style="font-size:80%;">process_kwargs</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx25.3" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx25.4" style="font-size:80%;">=</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx25.5" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx25.6" style="font-size:80%;">{</span> </div> <div class="ltx_listingline" id="lstnumberx26"> <span class="ltx_tag ltx_tag_listingline">26</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx26.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx26.2" style="font-size:80%;color:#D15120;">’manifold_leaves’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx26.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx26.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx26.5" style="font-size:80%;">1000,</span> </div> <div class="ltx_listingline" id="lstnumberx27"> <span class="ltx_tag ltx_tag_listingline">27</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx27.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx27.2" style="font-size:80%;color:#D15120;">’ratio’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx27.3" style="font-size:80%;">:</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx27.4" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx27.5" style="font-size:80%;">0.2,</span> </div> <div class="ltx_listingline" id="lstnumberx28"> <span class="ltx_tag ltx_tag_listingline">28</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx28.1" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx28.2" style="font-size:80%;">}</span> </div> <div class="ltx_listingline" id="lstnumberx29"> <span class="ltx_tag ltx_tag_listingline">29</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx29.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_comment ltx_font_typewriter ltx_font_bold" id="lstnumberx29.2" style="font-size:80%;color:#6D6D6D;">#<span class="ltx_text ltx_lst_space" id="lstnumberx29.2.1"> </span>Call<span class="ltx_text ltx_lst_space" id="lstnumberx29.2.2"> </span>spherize_mesh<span class="ltx_text ltx_lst_space" id="lstnumberx29.2.3"> </span>with<span class="ltx_text ltx_lst_space" id="lstnumberx29.2.4"> </span>kwargs</span> </div> <div class="ltx_listingline" id="lstnumberx30"> <span class="ltx_tag ltx_tag_listingline">30</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx30.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx30.2" style="font-size:80%;">spheres</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx30.3" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx30.4" style="font-size:80%;">=</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx30.5" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx30.6" style="font-size:80%;">spherize_mesh</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx30.7" style="font-size:80%;">(</span> </div> <div class="ltx_listingline" id="lstnumberx31"> <span class="ltx_tag ltx_tag_listingline">31</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx31.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx31.2" style="font-size:80%;">mesh_filepath</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx31.3" style="font-size:80%;">,</span> </div> <div class="ltx_listingline" id="lstnumberx32"> <span class="ltx_tag ltx_tag_listingline">32</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx32.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx32.2" style="font-size:80%;">spherization_kwargs</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx32.3" style="font-size:80%;">=</span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx32.4" style="font-size:80%;">sphere_kwargs</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx32.5" style="font-size:80%;">,</span> </div> <div class="ltx_listingline" id="lstnumberx33"> <span class="ltx_tag ltx_tag_listingline">33</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx33.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx33.2" style="font-size:80%;">process_kwargs</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx33.3" style="font-size:80%;">=</span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx33.4" style="font-size:80%;">process_kwargs</span> </div> <div class="ltx_listingline" id="lstnumberx34"> <span class="ltx_tag ltx_tag_listingline">34</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx34.1" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx34.2" style="font-size:80%;">)</span> </div> <div class="ltx_listingline" id="lstnumberx35"> <span class="ltx_tag ltx_tag_listingline">35</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx35.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_comment ltx_font_typewriter ltx_font_bold" id="lstnumberx35.2" style="font-size:80%;color:#6D6D6D;">#<span class="ltx_text ltx_lst_space" id="lstnumberx35.2.1"> </span>Write<span class="ltx_text ltx_lst_space" id="lstnumberx35.2.2"> </span>the<span class="ltx_text ltx_lst_space" id="lstnumberx35.2.3"> </span>result<span class="ltx_text ltx_lst_space" id="lstnumberx35.2.4"> </span>to<span class="ltx_text ltx_lst_space" id="lstnumberx35.2.5"> </span>a<span class="ltx_text ltx_lst_space" id="lstnumberx35.2.6"> </span>JSON<span class="ltx_text ltx_lst_space" id="lstnumberx35.2.7"> </span>file</span> </div> <div class="ltx_listingline" id="lstnumberx36"> <span class="ltx_tag ltx_tag_listingline">36</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx36.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx36.2" style="font-size:80%;">output</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx36.3" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx36.4" style="font-size:80%;">=</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx36.5" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx36.6" style="font-size:80%;">mesh_filepath</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx36.7" style="font-size:80%;">.</span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx36.8" style="font-size:80%;">stem</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx36.9" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx36.10" style="font-size:80%;">+</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx36.11" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx36.12" style="font-size:80%;color:#D15120;">"-spheres"</span> </div> <div class="ltx_listingline" id="lstnumberx37"> <span class="ltx_tag ltx_tag_listingline">37</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx37.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx37.2" style="font-size:80%;">with</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx37.3" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_keyword ltx_lst_keywords2 ltx_font_typewriter ltx_font_bold" id="lstnumberx37.4" style="font-size:80%;color:#417598;">open</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx37.5" style="font-size:80%;">(</span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx37.6" style="font-size:80%;">output</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx37.7" style="font-size:80%;"> </span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx37.8" style="font-size:80%;">+</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx37.9" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx37.10" style="font-size:80%;color:#D15120;">".json"</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx37.11" style="font-size:80%;">,</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx37.12" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_string ltx_font_typewriter ltx_font_bold" id="lstnumberx37.13" style="font-size:80%;color:#D15120;">’w’</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx37.14" style="font-size:80%;">)</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx37.15" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx37.16" style="font-size:80%;">as</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx37.17" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx37.18" style="font-size:80%;">f</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx37.19" style="font-size:80%;">:</span> </div> <div class="ltx_listingline" id="lstnumberx38"> <span class="ltx_tag ltx_tag_listingline">38</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx38.1" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx38.2" style="font-size:80%;">f</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx38.3" style="font-size:80%;">.</span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx38.4" style="font-size:80%;">write</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx38.5" style="font-size:80%;">(</span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx38.6" style="font-size:80%;">dumps</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx38.7" style="font-size:80%;">(</span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx38.8" style="font-size:80%;">spheres</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx38.9" style="font-size:80%;">,</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx38.10" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx38.11" style="font-size:80%;">indent</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx38.12" style="font-size:80%;">=4,</span><span class="ltx_text ltx_lst_space ltx_font_typewriter ltx_font_bold" id="lstnumberx38.13" style="font-size:80%;"> </span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx38.14" style="font-size:80%;">cls</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx38.15" style="font-size:80%;">=</span><span class="ltx_text ltx_lst_identifier ltx_font_typewriter ltx_font_bold" id="lstnumberx38.16" style="font-size:80%;">SphereEncoder</span><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="lstnumberx38.17" style="font-size:80%;">))</span> </div> </div> <figcaption class="ltx_caption"><span class="ltx_tag ltx_tag_figure">Figure 5: </span>Example script to process a mesh using <span class="ltx_text ltx_font_typewriter" id="S3.F5.3.1">foam</span>.</figcaption> </figure> <div class="ltx_para" id="S3.SS4.p1"> <p class="ltx_p" id="S3.SS4.p1.1">We provide the mesh preprocessing pipeline and spherization tools as the <span class="ltx_text ltx_font_typewriter" id="S3.SS4.p1.1.1">foam</span> Python library and command-line tool, along with a Docker container to provide easy use to end users. The code is available in <a class="ltx_ref ltx_url ltx_font_typewriter" href="https://github.com/CoMMALab/foam/" title="">https://github.com/CoMMALab/foam/</a>. A simple example script that demonstrates how <span class="ltx_text ltx_font_typewriter" id="S3.SS4.p1.1.2">foam</span> can be used as a library to convert a mesh into a set of spheres is given in <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S3.F5" title="In III-D The Foam Tool ‣ III The Foam Library ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">5</span></a>. After defining the <span class="ltx_text ltx_font_typewriter" id="S3.SS4.p1.1.3">spherization_kwargs</span> and <span class="ltx_text ltx_font_typewriter" id="S3.SS4.p1.1.4">process_kwargs</span>, the <span class="ltx_text ltx_font_typewriter ltx_font_bold" id="S3.SS4.p1.1.5">spherize_mesh()</span> function is called and the spheres are written to a JSON file.</p> </div> <div class="ltx_para" id="S3.SS4.p2"> <p class="ltx_p" id="S3.SS4.p2.1">Beyond the <span class="ltx_text ltx_font_typewriter" id="S3.SS4.p2.1.1">foam</span> library, we provide standalone scripts that can be used to spherize an input mesh or URDF: <br class="ltx_break"/><span class="ltx_text ltx_font_typewriter ltx_font_bold" id="S3.SS4.p2.1.2">$ python generate_spheres.py <mesh> <br class="ltx_break"/>$ python generate_sphere_urdf.py <urdf></span></p> </div> <div class="ltx_para" id="S3.SS4.p3"> <p class="ltx_p" id="S3.SS4.p3.1"><span class="ltx_text ltx_font_typewriter" id="S3.SS4.p3.1.1">foam</span> has already proven useful for other publications. For example, <span class="ltx_text ltx_font_typewriter" id="S3.SS4.p3.1.2">foam</span> was used to generate the spherized geometry for the UR5, Fetch, Baxter robots as well as some environments used in <span class="ltx_ERROR undefined" id="S3.SS4.p3.1.3">\citet</span>thomason2024motions,ramsey2024,quintero2024impdist.</p> </div> </section> </section> <section class="ltx_section" id="S4"> <h2 class="ltx_title ltx_title_section"> <span class="ltx_tag ltx_tag_section">IV </span><span class="ltx_text ltx_font_smallcaps" id="S4.1.1">Empirical Results</span> </h2> <div class="ltx_para" id="S4.p1"> <p class="ltx_p" id="S4.p1.1">We observe <span class="ltx_text ltx_font_typewriter" id="S4.p1.1.1">foam</span>’s effectiveness across a variety of fundamental robotics tasks in various simulators and collision checking backends. We selected MuJoCo <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">todorov2012mujoco</span>]</cite>, PyBullet <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">Coumans2016</span>]</cite>, and Pinocchio <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">carpentier2019pinocchio</span>]</cite> as these are widely used throughout the field—MuJoCo and PyBullet are popular off-the-shelf robotics-focused physics simulators due to their wide functionality, high fidelity, and accessibility. Pinocchio is a library for robot kinematics and dynamics modeling and uses the FCL library for collision checking <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">fcl</span>]</cite>. We present results in <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S4.T1" title="In IV Empirical Results ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Table</span> <span class="ltx_text ltx_ref_tag">I</span></a> that show the difference in collision checking and signed distance query speed over these three libraries for five robots: the Hello Robot Stretch, the Franka Emika Panda, the KUKA IIWA, the Kinova Jaco, and the Rethink Robotics Baxter. Examples of the spherized models for the Panda, KUKA, and Kinova are shown in <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S1.F1" title="In I Introduction ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">1</span></a>. While collision checking speed remains relatively consistent in PyBullet and MuJoCo between the spherized models and base models, signed distance query time is significantly faster in all engines. FCL in particular is highly compatible with the spherized primitive representation, giving large performance gains over all robots except for the Stretch.</p> </div> <div class="ltx_para" id="S4.p2"> <p class="ltx_p" id="S4.p2.1">Additionally, we also investigate how model simplification can affect physics iteration time in a parallelized simulator, Genesis <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">Genesis</span>]</cite>, shown in <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S4.T2" title="In IV Empirical Results ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Table</span> <span class="ltx_text ltx_ref_tag">II</span></a>. The demand for parallelized simulators has seen a recent uptick as parallelized training for large models has become more prevalent, requiring a large-scale high-speed simulation for training and validation—simplified models may be a way to increase performance in certain tasks. Benchmarking the frames per second (FPS) in Genesis with 300 parallel simulations of the Franka Panda shows a 10% speedup when using a simplified model with 30 spheres, compared to the original model, shown in <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S4.T2" title="In IV Empirical Results ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Table</span> <span class="ltx_text ltx_ref_tag">II</span></a>. Spherization also improved FPS across all models. These results demonstrate that spherized models outperform the original, offering better computational efficiency in applications that demand numerous parallelized environments.</p> </div> <div class="ltx_para" id="S4.p3"> <p class="ltx_p" id="S4.p3.1">All experiments were performed on a PC with a 13th Gen Intel(R) Core(TM) i7-13700K CPU, an NVIDIA GeForce RTX 4070Ti, and 32GB of system memory.</p> </div> <figure class="ltx_table" id="S4.T1"> <table class="ltx_tabular ltx_centering ltx_guessed_headers ltx_align_middle" id="S4.T1.9"> <thead class="ltx_thead"> <tr class="ltx_tr" id="S4.T1.9.10.1"> <th class="ltx_td ltx_th ltx_th_column ltx_border_rr" id="S4.T1.9.10.1.1" style="padding-top:1.5pt;padding-bottom:1.5pt;"></th> <th class="ltx_td ltx_align_center ltx_th ltx_th_column" colspan="3" id="S4.T1.9.10.1.2" style="padding-top:1.5pt;padding-bottom:1.5pt;">PyBullet</th> <th class="ltx_td ltx_align_center ltx_th ltx_th_column" colspan="3" id="S4.T1.9.10.1.3" style="padding-top:1.5pt;padding-bottom:1.5pt;">MuJoCo</th> <th class="ltx_td ltx_align_center ltx_th ltx_th_column" colspan="3" id="S4.T1.9.10.1.4" style="padding-top:1.5pt;padding-bottom:1.5pt;">Pinocchio (FCL)</th> </tr> <tr class="ltx_tr" id="S4.T1.9.9"> <th class="ltx_td ltx_align_right ltx_th ltx_th_column ltx_border_rr" id="S4.T1.9.9.10" style="padding-top:1.5pt;padding-bottom:1.5pt;">Robot</th> <th class="ltx_td ltx_align_right ltx_th ltx_th_column" id="S4.T1.1.1.1" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <math alttext="\Delta" class="ltx_Math" display="inline" id="S4.T1.1.1.1.m1.1"><semantics id="S4.T1.1.1.1.m1.1a"><mi id="S4.T1.1.1.1.m1.1.1" mathvariant="normal" xref="S4.T1.1.1.1.m1.1.1.cmml">Δ</mi><annotation-xml encoding="MathML-Content" id="S4.T1.1.1.1.m1.1b"><ci id="S4.T1.1.1.1.m1.1.1.cmml" xref="S4.T1.1.1.1.m1.1.1">Δ</ci></annotation-xml><annotation encoding="application/x-tex" id="S4.T1.1.1.1.m1.1c">\Delta</annotation><annotation encoding="application/x-llamapun" id="S4.T1.1.1.1.m1.1d">roman_Δ</annotation></semantics></math> Col. (ms)</th> <th class="ltx_td ltx_align_right ltx_th ltx_th_column" id="S4.T1.2.2.2" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <math alttext="\Delta" class="ltx_Math" display="inline" id="S4.T1.2.2.2.m1.1"><semantics id="S4.T1.2.2.2.m1.1a"><mi id="S4.T1.2.2.2.m1.1.1" mathvariant="normal" xref="S4.T1.2.2.2.m1.1.1.cmml">Δ</mi><annotation-xml encoding="MathML-Content" id="S4.T1.2.2.2.m1.1b"><ci id="S4.T1.2.2.2.m1.1.1.cmml" xref="S4.T1.2.2.2.m1.1.1">Δ</ci></annotation-xml><annotation encoding="application/x-tex" id="S4.T1.2.2.2.m1.1c">\Delta</annotation><annotation encoding="application/x-llamapun" id="S4.T1.2.2.2.m1.1d">roman_Δ</annotation></semantics></math> Dis. (ms)</th> <th class="ltx_td ltx_align_justify ltx_th ltx_th_column ltx_border_r" id="S4.T1.3.3.3" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.3.3.3.1"> <span class="ltx_p" id="S4.T1.3.3.3.1.1"><math alttext="\%" class="ltx_Math" display="inline" id="S4.T1.3.3.3.1.1.m1.1"><semantics id="S4.T1.3.3.3.1.1.m1.1a"><mo id="S4.T1.3.3.3.1.1.m1.1.1" xref="S4.T1.3.3.3.1.1.m1.1.1.cmml">%</mo><annotation-xml encoding="MathML-Content" id="S4.T1.3.3.3.1.1.m1.1b"><csymbol cd="latexml" id="S4.T1.3.3.3.1.1.m1.1.1.cmml" xref="S4.T1.3.3.3.1.1.m1.1.1">percent</csymbol></annotation-xml><annotation encoding="application/x-tex" id="S4.T1.3.3.3.1.1.m1.1c">\%</annotation><annotation encoding="application/x-llamapun" id="S4.T1.3.3.3.1.1.m1.1d">%</annotation></semantics></math> Diff.</span> </span> </th> <th class="ltx_td ltx_align_right ltx_th ltx_th_column" id="S4.T1.4.4.4" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <math alttext="\Delta" class="ltx_Math" display="inline" id="S4.T1.4.4.4.m1.1"><semantics id="S4.T1.4.4.4.m1.1a"><mi id="S4.T1.4.4.4.m1.1.1" mathvariant="normal" xref="S4.T1.4.4.4.m1.1.1.cmml">Δ</mi><annotation-xml encoding="MathML-Content" id="S4.T1.4.4.4.m1.1b"><ci id="S4.T1.4.4.4.m1.1.1.cmml" xref="S4.T1.4.4.4.m1.1.1">Δ</ci></annotation-xml><annotation encoding="application/x-tex" id="S4.T1.4.4.4.m1.1c">\Delta</annotation><annotation encoding="application/x-llamapun" id="S4.T1.4.4.4.m1.1d">roman_Δ</annotation></semantics></math> Col. (ms)</th> <th class="ltx_td ltx_align_right ltx_th ltx_th_column" id="S4.T1.5.5.5" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <math alttext="\Delta" class="ltx_Math" display="inline" id="S4.T1.5.5.5.m1.1"><semantics id="S4.T1.5.5.5.m1.1a"><mi id="S4.T1.5.5.5.m1.1.1" mathvariant="normal" xref="S4.T1.5.5.5.m1.1.1.cmml">Δ</mi><annotation-xml encoding="MathML-Content" id="S4.T1.5.5.5.m1.1b"><ci id="S4.T1.5.5.5.m1.1.1.cmml" xref="S4.T1.5.5.5.m1.1.1">Δ</ci></annotation-xml><annotation encoding="application/x-tex" id="S4.T1.5.5.5.m1.1c">\Delta</annotation><annotation encoding="application/x-llamapun" id="S4.T1.5.5.5.m1.1d">roman_Δ</annotation></semantics></math> Dis. (ms)</th> <th class="ltx_td ltx_align_justify ltx_th ltx_th_column ltx_border_r" id="S4.T1.6.6.6" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.6.6.6.1"> <span class="ltx_p" id="S4.T1.6.6.6.1.1"><math alttext="\%" class="ltx_Math" display="inline" id="S4.T1.6.6.6.1.1.m1.1"><semantics id="S4.T1.6.6.6.1.1.m1.1a"><mo id="S4.T1.6.6.6.1.1.m1.1.1" xref="S4.T1.6.6.6.1.1.m1.1.1.cmml">%</mo><annotation-xml encoding="MathML-Content" id="S4.T1.6.6.6.1.1.m1.1b"><csymbol cd="latexml" id="S4.T1.6.6.6.1.1.m1.1.1.cmml" xref="S4.T1.6.6.6.1.1.m1.1.1">percent</csymbol></annotation-xml><annotation encoding="application/x-tex" id="S4.T1.6.6.6.1.1.m1.1c">\%</annotation><annotation encoding="application/x-llamapun" id="S4.T1.6.6.6.1.1.m1.1d">%</annotation></semantics></math> Diff.</span> </span> </th> <th class="ltx_td ltx_align_right ltx_th ltx_th_column" id="S4.T1.7.7.7" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <math alttext="\Delta" class="ltx_Math" display="inline" id="S4.T1.7.7.7.m1.1"><semantics id="S4.T1.7.7.7.m1.1a"><mi id="S4.T1.7.7.7.m1.1.1" mathvariant="normal" xref="S4.T1.7.7.7.m1.1.1.cmml">Δ</mi><annotation-xml encoding="MathML-Content" id="S4.T1.7.7.7.m1.1b"><ci id="S4.T1.7.7.7.m1.1.1.cmml" xref="S4.T1.7.7.7.m1.1.1">Δ</ci></annotation-xml><annotation encoding="application/x-tex" id="S4.T1.7.7.7.m1.1c">\Delta</annotation><annotation encoding="application/x-llamapun" id="S4.T1.7.7.7.m1.1d">roman_Δ</annotation></semantics></math> Col. (ms)</th> <th class="ltx_td ltx_align_right ltx_th ltx_th_column" id="S4.T1.8.8.8" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <math alttext="\Delta" class="ltx_Math" display="inline" id="S4.T1.8.8.8.m1.1"><semantics id="S4.T1.8.8.8.m1.1a"><mi id="S4.T1.8.8.8.m1.1.1" mathvariant="normal" xref="S4.T1.8.8.8.m1.1.1.cmml">Δ</mi><annotation-xml encoding="MathML-Content" id="S4.T1.8.8.8.m1.1b"><ci id="S4.T1.8.8.8.m1.1.1.cmml" xref="S4.T1.8.8.8.m1.1.1">Δ</ci></annotation-xml><annotation encoding="application/x-tex" id="S4.T1.8.8.8.m1.1c">\Delta</annotation><annotation encoding="application/x-llamapun" id="S4.T1.8.8.8.m1.1d">roman_Δ</annotation></semantics></math> Dis. (ms)</th> <th class="ltx_td ltx_align_justify ltx_th ltx_th_column" id="S4.T1.9.9.9" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.9.9.1"> <span class="ltx_p" id="S4.T1.9.9.9.1.1"><math alttext="\%" class="ltx_Math" display="inline" id="S4.T1.9.9.9.1.1.m1.1"><semantics id="S4.T1.9.9.9.1.1.m1.1a"><mo id="S4.T1.9.9.9.1.1.m1.1.1" xref="S4.T1.9.9.9.1.1.m1.1.1.cmml">%</mo><annotation-xml encoding="MathML-Content" id="S4.T1.9.9.9.1.1.m1.1b"><csymbol cd="latexml" id="S4.T1.9.9.9.1.1.m1.1.1.cmml" xref="S4.T1.9.9.9.1.1.m1.1.1">percent</csymbol></annotation-xml><annotation encoding="application/x-tex" id="S4.T1.9.9.9.1.1.m1.1c">\%</annotation><annotation encoding="application/x-llamapun" id="S4.T1.9.9.9.1.1.m1.1d">%</annotation></semantics></math> Diff.</span> </span> </th> </tr> </thead> <tbody class="ltx_tbody"> <tr class="ltx_tr" id="S4.T1.9.11.1"> <td class="ltx_td ltx_align_right ltx_border_rr ltx_border_t" id="S4.T1.9.11.1.1" style="padding-top:1.5pt;padding-bottom:1.5pt;">Stretch</td> <td class="ltx_td ltx_align_right ltx_border_t" id="S4.T1.9.11.1.2" style="padding-top:1.5pt;padding-bottom:1.5pt;">-0.002</td> <td class="ltx_td ltx_align_right ltx_border_t" id="S4.T1.9.11.1.3" style="padding-top:1.5pt;padding-bottom:1.5pt;">-4.286</td> <td class="ltx_td ltx_align_justify ltx_border_r ltx_border_t" id="S4.T1.9.11.1.4" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.11.1.4.1"> <span class="ltx_p" id="S4.T1.9.11.1.4.1.1">-0.00001%</span> </span> </td> <td class="ltx_td ltx_align_right ltx_border_t" id="S4.T1.9.11.1.5" style="padding-top:1.5pt;padding-bottom:1.5pt;">2.329</td> <td class="ltx_td ltx_align_right ltx_border_t" id="S4.T1.9.11.1.6" style="padding-top:1.5pt;padding-bottom:1.5pt;">-96.189</td> <td class="ltx_td ltx_align_justify ltx_border_r ltx_border_t" id="S4.T1.9.11.1.7" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.11.1.7.1"> <span class="ltx_p" id="S4.T1.9.11.1.7.1.1">0.00251%</span> </span> </td> <td class="ltx_td ltx_align_right ltx_border_t" id="S4.T1.9.11.1.8" style="padding-top:1.5pt;padding-bottom:1.5pt;">0.649</td> <td class="ltx_td ltx_align_right ltx_border_t" id="S4.T1.9.11.1.9" style="padding-top:1.5pt;padding-bottom:1.5pt;">-2.479</td> <td class="ltx_td ltx_align_justify ltx_border_t" id="S4.T1.9.11.1.10" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.11.1.10.1"> <span class="ltx_p" id="S4.T1.9.11.1.10.1.1">0.00386%</span> </span> </td> </tr> <tr class="ltx_tr" id="S4.T1.9.12.2"> <td class="ltx_td ltx_align_right ltx_border_rr" id="S4.T1.9.12.2.1" style="padding-top:1.5pt;padding-bottom:1.5pt;">Panda</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.12.2.2" style="padding-top:1.5pt;padding-bottom:1.5pt;">-0.002</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.12.2.3" style="padding-top:1.5pt;padding-bottom:1.5pt;">-1.274</td> <td class="ltx_td ltx_align_justify ltx_border_r" id="S4.T1.9.12.2.4" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.12.2.4.1"> <span class="ltx_p" id="S4.T1.9.12.2.4.1.1">0.00000%</span> </span> </td> <td class="ltx_td ltx_align_right" id="S4.T1.9.12.2.5" style="padding-top:1.5pt;padding-bottom:1.5pt;">0.011</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.12.2.6" style="padding-top:1.5pt;padding-bottom:1.5pt;">-14.785</td> <td class="ltx_td ltx_align_justify ltx_border_r" id="S4.T1.9.12.2.7" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.12.2.7.1"> <span class="ltx_p" id="S4.T1.9.12.2.7.1.1">0.00006%</span> </span> </td> <td class="ltx_td ltx_align_right" id="S4.T1.9.12.2.8" style="padding-top:1.5pt;padding-bottom:1.5pt;">-1.901</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.12.2.9" style="padding-top:1.5pt;padding-bottom:1.5pt;">-2.558</td> <td class="ltx_td ltx_align_justify" id="S4.T1.9.12.2.10" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.12.2.10.1"> <span class="ltx_p" id="S4.T1.9.12.2.10.1.1">0.00008%</span> </span> </td> </tr> <tr class="ltx_tr" id="S4.T1.9.13.3"> <td class="ltx_td ltx_align_right ltx_border_rr" id="S4.T1.9.13.3.1" style="padding-top:1.5pt;padding-bottom:1.5pt;">KUKA</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.13.3.2" style="padding-top:1.5pt;padding-bottom:1.5pt;">-0.000</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.13.3.3" style="padding-top:1.5pt;padding-bottom:1.5pt;">-1.586</td> <td class="ltx_td ltx_align_justify ltx_border_r" id="S4.T1.9.13.3.4" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.13.3.4.1"> <span class="ltx_p" id="S4.T1.9.13.3.4.1.1">0.00000%</span> </span> </td> <td class="ltx_td ltx_align_right" id="S4.T1.9.13.3.5" style="padding-top:1.5pt;padding-bottom:1.5pt;">0.005</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.13.3.6" style="padding-top:1.5pt;padding-bottom:1.5pt;">-1.985</td> <td class="ltx_td ltx_align_justify ltx_border_r" id="S4.T1.9.13.3.7" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.13.3.7.1"> <span class="ltx_p" id="S4.T1.9.13.3.7.1.1">0.00003%</span> </span> </td> <td class="ltx_td ltx_align_right" id="S4.T1.9.13.3.8" style="padding-top:1.5pt;padding-bottom:1.5pt;">-0.636</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.13.3.9" style="padding-top:1.5pt;padding-bottom:1.5pt;">-27.824</td> <td class="ltx_td ltx_align_justify" id="S4.T1.9.13.3.10" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.13.3.10.1"> <span class="ltx_p" id="S4.T1.9.13.3.10.1.1">0.00002%</span> </span> </td> </tr> <tr class="ltx_tr" id="S4.T1.9.14.4"> <td class="ltx_td ltx_align_right ltx_border_rr" id="S4.T1.9.14.4.1" style="padding-top:1.5pt;padding-bottom:1.5pt;">Kinova</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.14.4.2" style="padding-top:1.5pt;padding-bottom:1.5pt;">0.000</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.14.4.3" style="padding-top:1.5pt;padding-bottom:1.5pt;">-4.309</td> <td class="ltx_td ltx_align_justify ltx_border_r" id="S4.T1.9.14.4.4" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.14.4.4.1"> <span class="ltx_p" id="S4.T1.9.14.4.4.1.1">0.00000%</span> </span> </td> <td class="ltx_td ltx_align_right" id="S4.T1.9.14.4.5" style="padding-top:1.5pt;padding-bottom:1.5pt;">-0.005</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.14.4.6" style="padding-top:1.5pt;padding-bottom:1.5pt;">-0.233</td> <td class="ltx_td ltx_align_justify ltx_border_r" id="S4.T1.9.14.4.7" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.14.4.7.1"> <span class="ltx_p" id="S4.T1.9.14.4.7.1.1">0.00002%</span> </span> </td> <td class="ltx_td ltx_align_right" id="S4.T1.9.14.4.8" style="padding-top:1.5pt;padding-bottom:1.5pt;">-11.561</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.14.4.9" style="padding-top:1.5pt;padding-bottom:1.5pt;">-44.469</td> <td class="ltx_td ltx_align_justify" id="S4.T1.9.14.4.10" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.14.4.10.1"> <span class="ltx_p" id="S4.T1.9.14.4.10.1.1">0.00006%</span> </span> </td> </tr> <tr class="ltx_tr" id="S4.T1.9.15.5"> <td class="ltx_td ltx_align_right ltx_border_rr" id="S4.T1.9.15.5.1" style="padding-top:1.5pt;padding-bottom:1.5pt;">Baxter</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.15.5.2" style="padding-top:1.5pt;padding-bottom:1.5pt;">-0.001</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.15.5.3" style="padding-top:1.5pt;padding-bottom:1.5pt;">-6.879</td> <td class="ltx_td ltx_align_justify ltx_border_r" id="S4.T1.9.15.5.4" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.15.5.4.1"> <span class="ltx_p" id="S4.T1.9.15.5.4.1.1">-0.00005%</span> </span> </td> <td class="ltx_td ltx_align_right" id="S4.T1.9.15.5.5" style="padding-top:1.5pt;padding-bottom:1.5pt;">7.363</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.15.5.6" style="padding-top:1.5pt;padding-bottom:1.5pt;">-14.260</td> <td class="ltx_td ltx_align_justify ltx_border_r" id="S4.T1.9.15.5.7" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.15.5.7.1"> <span class="ltx_p" id="S4.T1.9.15.5.7.1.1">0.00008%</span> </span> </td> <td class="ltx_td ltx_align_right" id="S4.T1.9.15.5.8" style="padding-top:1.5pt;padding-bottom:1.5pt;">-1.431</td> <td class="ltx_td ltx_align_right" id="S4.T1.9.15.5.9" style="padding-top:1.5pt;padding-bottom:1.5pt;">-1.045</td> <td class="ltx_td ltx_align_justify" id="S4.T1.9.15.5.10" style="padding-top:1.5pt;padding-bottom:1.5pt;"> <span class="ltx_inline-block ltx_align_top" id="S4.T1.9.15.5.10.1"> <span class="ltx_p" id="S4.T1.9.15.5.10.1.1">0.00014%</span> </span> </td> </tr> </tbody> </table> <figcaption class="ltx_caption ltx_centering"><span class="ltx_tag ltx_tag_table">TABLE I: </span>Comparison of collision checking and signed distance computation in three simulation and modeling frameworks: PyBullet <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">Coumans2016</span>]</cite>, MuJoCo <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">todorov2012mujoco</span>]</cite>, and Pinocchio <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">carpentier2019pinocchio</span>]</cite>, which uses FCL <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">fcl</span>]</cite> for collision checking. For each robot in each simulator, we evaluate the original robot URDF against the spherized URDF generated by <span class="ltx_text ltx_font_typewriter" id="S4.T1.16.1">foam</span> over 100,000 queries in randomly generated environments, visualized in <a class="ltx_ref" href="https://arxiv.org/html/2503.13704v1#S4.F6" title="In IV Empirical Results ‣ foam: A Tool for Spherical Approximation of Robot Geometry"><span class="ltx_text ltx_ref_tag">Fig.</span> <span class="ltx_text ltx_ref_tag">6</span></a>. We report the change in average query time for collision checking (<math alttext="\Delta" class="ltx_Math" display="inline" id="S4.T1.12.m1.1"><semantics id="S4.T1.12.m1.1b"><mi id="S4.T1.12.m1.1.1" mathvariant="normal" xref="S4.T1.12.m1.1.1.cmml">Δ</mi><annotation-xml encoding="MathML-Content" id="S4.T1.12.m1.1c"><ci id="S4.T1.12.m1.1.1.cmml" xref="S4.T1.12.m1.1.1">Δ</ci></annotation-xml><annotation encoding="application/x-tex" id="S4.T1.12.m1.1d">\Delta</annotation><annotation encoding="application/x-llamapun" id="S4.T1.12.m1.1e">roman_Δ</annotation></semantics></math> Col.) and the change in average distance query time (<math alttext="\Delta" class="ltx_Math" display="inline" id="S4.T1.13.m2.1"><semantics id="S4.T1.13.m2.1b"><mi id="S4.T1.13.m2.1.1" mathvariant="normal" xref="S4.T1.13.m2.1.1.cmml">Δ</mi><annotation-xml encoding="MathML-Content" id="S4.T1.13.m2.1c"><ci id="S4.T1.13.m2.1.1.cmml" xref="S4.T1.13.m2.1.1">Δ</ci></annotation-xml><annotation encoding="application/x-tex" id="S4.T1.13.m2.1d">\Delta</annotation><annotation encoding="application/x-llamapun" id="S4.T1.13.m2.1e">roman_Δ</annotation></semantics></math> Dis.) in milliseconds between the original and spherized model (negative meaning the spherized model is faster), and the percentage difference in collision check validity between the models (positive meaning more states are in collision with the spherized model). PyBullet implicitly convexifies all collision geometry and thus leads to the negative difference in collision, compared to the conservative but accurate spherized model generated by <span class="ltx_text ltx_font_typewriter" id="S4.T1.17.2">foam</span>. We also note that sometimes the spherized model is less efficient for collision checking due to efficient spatial data structures used in collision testing, but distance queries are always faster. </figcaption> </figure> <figure class="ltx_table" id="S4.T2"> <table class="ltx_tabular ltx_centering ltx_guessed_headers ltx_align_middle" id="S4.T2.1"> <thead class="ltx_thead"> <tr class="ltx_tr" id="S4.T2.1.1.1"> <th class="ltx_td ltx_align_right ltx_th ltx_th_column ltx_th_row ltx_border_r" id="S4.T2.1.1.1.1" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.1.1.1.1" style="font-size:80%;">Robot Model</span></th> <th class="ltx_td ltx_align_left ltx_th ltx_th_column" id="S4.T2.1.1.1.2" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.1.1.2.1" style="font-size:80%;">Millions of FPS</span></th> </tr> </thead> <tbody class="ltx_tbody"> <tr class="ltx_tr" id="S4.T2.1.2.1"> <th class="ltx_td ltx_align_right ltx_th ltx_th_row ltx_border_r ltx_border_t" id="S4.T2.1.2.1.1" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.2.1.1.1" style="font-size:80%;">Panda</span></th> <td class="ltx_td ltx_align_left ltx_border_t" id="S4.T2.1.2.1.2" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.2.1.2.1" style="font-size:80%;">5.20</span></td> </tr> <tr class="ltx_tr" id="S4.T2.1.3.2"> <th class="ltx_td ltx_align_right ltx_th ltx_th_row ltx_border_r" id="S4.T2.1.3.2.1" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.3.2.1.1" style="font-size:80%;">11 Spheres</span></th> <td class="ltx_td ltx_align_left" id="S4.T2.1.3.2.2" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.3.2.2.1" style="font-size:80%;">6.36</span></td> </tr> <tr class="ltx_tr" id="S4.T2.1.4.3"> <th class="ltx_td ltx_align_right ltx_th ltx_th_row ltx_border_r" id="S4.T2.1.4.3.1" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.4.3.1.1" style="font-size:80%;">22 Spheres</span></th> <td class="ltx_td ltx_align_left" id="S4.T2.1.4.3.2" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.4.3.2.1" style="font-size:80%;">5.36</span></td> </tr> <tr class="ltx_tr" id="S4.T2.1.5.4"> <th class="ltx_td ltx_align_right ltx_th ltx_th_row ltx_border_r" id="S4.T2.1.5.4.1" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.5.4.1.1" style="font-size:80%;">27 Spheres</span></th> <td class="ltx_td ltx_align_left" id="S4.T2.1.5.4.2" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.5.4.2.1" style="font-size:80%;">5.83</span></td> </tr> <tr class="ltx_tr" id="S4.T2.1.6.5"> <th class="ltx_td ltx_align_right ltx_th ltx_th_row ltx_border_r" id="S4.T2.1.6.5.1" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.6.5.1.1" style="font-size:80%;">30 Spheres</span></th> <td class="ltx_td ltx_align_left" id="S4.T2.1.6.5.2" style="padding-top:1.2pt;padding-bottom:1.2pt;"><span class="ltx_text" id="S4.T2.1.6.5.2.1" style="font-size:80%;">5.73</span></td> </tr> </tbody> </table> <figcaption class="ltx_caption ltx_centering" style="font-size:80%;"><span class="ltx_tag ltx_tag_table">TABLE II: </span>Simulation framerate in millions of frames per second for a Panda grasping task in the Genesis <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">Genesis</span>]</cite> simulator. Using the spherized collision model provides around 10% speedup over base model using the 30 spheres.</figcaption> </figure> <figure class="ltx_figure" id="S4.F6"><img alt="Refer to caption" class="ltx_graphics ltx_centering ltx_img_landscape" height="223" id="S4.F6.g1" src="extracted/6288087/images/collision_figure.png" width="598"/> <figcaption class="ltx_caption ltx_centering"><span class="ltx_tag ltx_tag_figure">Figure 6: </span>Left: Random environment used to evaluate collision checking, visualized in PyBullet. Right: the same environment with the Franka Emika Panda loaded inside.</figcaption> </figure> </section> <section class="ltx_section" id="S5"> <h2 class="ltx_title ltx_title_section"> <span class="ltx_tag ltx_tag_section">V </span><span class="ltx_text ltx_font_smallcaps" id="S5.1.1">Discussion</span> </h2> <div class="ltx_para" id="S5.p1"> <p class="ltx_p" id="S5.p1.1">We have presented <span class="ltx_text ltx_font_typewriter" id="S5.p1.1.1">foam</span>, a library and tool to generate spherical approximations of robot geometry from an input URDF, addressing a critical limitation in existing tools to bridge general robots to methods that require spherical approximations. <span class="ltx_text ltx_font_typewriter" id="S5.p1.1.2">foam</span> handles common mesh defects gracefully while preserving essential geometric features; our pipeline enables roboticists to easily convert complex CAD-derived meshes into computationally efficient primitive representations. <span class="ltx_text ltx_font_typewriter" id="S5.p1.1.3">foam</span> also provides a number configurable parameters allow users to balance geometric fidelity with computational efficiency according to downstream requirements.</p> </div> <div class="ltx_para" id="S5.p2"> <p class="ltx_p" id="S5.p2.1">Our empirical results also demonstrate that spherical approximations of robot geometries provide significant computational advantages while maintaining acceptable geometric fidelity for practical robotics tasks. Across multiple standard robots (Franka Emika Panda, Baxter, KUKA IIWA, Kinova, and Stretch), we observed substantial performance improvements in collision checking times, particularly for distance queries, with speedups of up to two orders of magnitude in some cases (e.g., Kinova through FCL-based collision checking in the Pinocchio framework). These findings suggest that simplified robot geometry should be preferred for robotics tasks unless absolute geometric precision is essential, especially for applications involving signed distance fields or real-time control.</p> </div> <div class="ltx_para" id="S5.p3"> <p class="ltx_p" id="S5.p3.1"><span class="ltx_text ltx_font_typewriter" id="S5.p3.1.1">foam</span> also opens the door for general robots to be applied to tools that require spherical models, such as cuRobo <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">sundaralingam2023curobo</span>]</cite>, GPMP2 <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">mukadam2018continuous</span>]</cite>, VAMP <cite class="ltx_cite ltx_citemacro_cite">[<span class="ltx_ref ltx_missing_citation ltx_ref_self">thomason2024motions</span>]</cite>, and more. In the future, we plan to provide not only spherical approximations in <span class="ltx_text ltx_font_typewriter" id="S5.p3.1.2">foam</span>, but also convex decompositions, cuboid decompositions, and other mesh processing tools. We are especially interested in other spherization algorithms that could be run more tightly “in-the-loop” to address situations that require faster spherization, such as dynamic manipulation requiring spherization of objects on the fly.</p> </div> </section> <section class="ltx_section" id="Sx1"> <h2 class="ltx_title ltx_font_smallcaps ltx_title_section">Acknowledgments</h2> <div class="ltx_para" id="Sx1.p1"> <p class="ltx_p" id="Sx1.p1.1">The authors thank Andrew Lu, Carlos Quintero-Peña, Pranav Jadhav, and Wil Thomason for helpful discussions and feedback.</p> </div> <div class="ltx_para" id="Sx1.p2"> <span class="ltx_ERROR undefined" id="Sx1.p2.1">\printbibliography</span> </div> </section> </article> </div> <footer class="ltx_page_footer"> <div class="ltx_page_logo">Generated on Mon Mar 17 20:18:46 2025 by <a class="ltx_LaTeXML_logo" href="http://dlmf.nist.gov/LaTeXML/"><span style="letter-spacing:-0.2em; margin-right:0.1em;">L<span class="ltx_font_smallcaps" style="position:relative; bottom:2.2pt;">a</span>T<span class="ltx_font_smallcaps" style="font-size:120%;position:relative; bottom:-0.2ex;">e</span></span><span style="font-size:90%; position:relative; bottom:-0.2ex;">XML</span><img alt="Mascot Sammy" src="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAsAAAAOCAYAAAD5YeaVAAAAAXNSR0IArs4c6QAAAAZiS0dEAP8A/wD/oL2nkwAAAAlwSFlzAAALEwAACxMBAJqcGAAAAAd0SU1FB9wKExQZLWTEaOUAAAAddEVYdENvbW1lbnQAQ3JlYXRlZCB3aXRoIFRoZSBHSU1Q72QlbgAAAdpJREFUKM9tkL+L2nAARz9fPZNCKFapUn8kyI0e4iRHSR1Kb8ng0lJw6FYHFwv2LwhOpcWxTjeUunYqOmqd6hEoRDhtDWdA8ApRYsSUCDHNt5ul13vz4w0vWCgUnnEc975arX6ORqN3VqtVZbfbTQC4uEHANM3jSqXymFI6yWazP2KxWAXAL9zCUa1Wy2tXVxheKA9YNoR8Pt+aTqe4FVVVvz05O6MBhqUIBGk8Hn8HAOVy+T+XLJfLS4ZhTiRJgqIoVBRFIoric47jPnmeB1mW/9rr9ZpSSn3Lsmir1fJZlqWlUonKsvwWwD8ymc/nXwVBeLjf7xEKhdBut9Hr9WgmkyGEkJwsy5eHG5vN5g0AKIoCAEgkEkin0wQAfN9/cXPdheu6P33fBwB4ngcAcByHJpPJl+fn54mD3Gg0NrquXxeLRQAAwzAYj8cwTZPwPH9/sVg8PXweDAauqqr2cDjEer1GJBLBZDJBs9mE4zjwfZ85lAGg2+06hmGgXq+j3+/DsixYlgVN03a9Xu8jgCNCyIegIAgx13Vfd7vdu+FweG8YRkjXdWy329+dTgeSJD3ieZ7RNO0VAXAPwDEAO5VKndi2fWrb9jWl9Esul6PZbDY9Go1OZ7PZ9z/lyuD3OozU2wAAAABJRU5ErkJggg=="/></a> </div></footer> </div> </body> </html>