Introduction
The design and construction of robots that can execute compelling motions is a challenging task. It requires careful geometric planning of robotic mechanisms and professional knowledge of the kinematic and dynamic behavior of the robot. Embedding such knowledge into procedures of computational robot design [1], [2] in conjunction with rapid prototyping techniques, such as 3D printing technology, bears tremendous potential to accelerate the construction of personalized robots. For instance, Megaro et al. [3] used a kinematic optimization algorithm for the design of multilegged robots consisting of rigid links. However, real-world creatures are not merely rigid skeleton rigs. The muscle and flesh surrounding the skeleton provides diverse morphologies, enriched expressivity. For instance, people wearing a prosthetic limb often prefer a highly realistic rubbery artificial arm over a more functional mechanical one [4]. Moreover, skins and muscles might be essential for facilitating challenging tasks, such as reproducing compliant grasping of a hand or swimming motions of a fish [5], [6].
Different to the simulation of the robots with rigid links only, the influence of the soft skin on the control torques at actuators and on the contact forces at the ground should be simulated and fully taken care of to judge the plausibility of a designed soft robot. This imposes a significant computational challenge for the motion design and fabrication of skinned robots. In this paper, our goal is to address this problem by integrating both dynamic simulation and kinematic optimization into the motion design of quad-robot systems, with soft skins attached as their organic embodiments. Its kernel is an optimization problem that integrates both user-provided kinematic preference and physical constraints of the robot to obtain a dynamically feasible motion plan. The primary physical constraint is the dynamic viability of the skeleton trajectory when a soft skin is attached. The dynamics of the robot is formulated as two-way coupled subsystems of the rigid multibody system and the deformable skin. In addition, our system also incorporates motor constraints and a stability constraint. The motor constraints ensure that the calculated joint torques are within the physical limits of the installed servo motors, whereas the stability constraint requires the center of projection (COP) of the robot structure to fall inside the supporting polygon. As a result, given the surface mesh and desired kinematic trajectories of the robot, our pipeline generates a physically-valid motion plan that can be realized under the given hardware constraints. The robot itself can be fabricated using rapid prototyping technology.
While space-time optimization is widely used in long-horizon motion design problem, it is computationally prohibitive if directly applied to our case of two-way coupled system, mostly due to the large number of DOFs of the soft skin mesh coupled with the skeleton and various physcial constraints. To this end, we propose an alternating optimization algorithm of two optimization steps to mitigate the computational cost: (1) Space-time optimization with repect to the DOFs of the rigid skeleton while assuming the deformation of the soft skin remains the same as the previous iteration. (2) Frame-by-frame optimization as in [7] to further optimize the motion plan obtained in step 1 according to all the physical constraints at each frame. To this end, we non-trivially extend the spring-based control force formulation in [7] to handle the full simulation of the two-way coupled rigid skeleton and soft skin. Our solver can efficiently handle the Lagrange multipliers introduced by the coupling constraints and the collisions between the skeleton and skin. With a proper initialization, these two steps are alternatively executed until the convergence. In the space-time optimization step, the influence of the soft skin to the rigid skeleton is treated as known quantity and simplified to be the coupling forces and the influence of the center of mass (COM) at each link in the skeleton due to the skin deformation. This setting makes the space-time optimization computationally efficient through decoupling the skin mesh DOFs, which is critical to achieve global effect in the motion design. The skin deformation is updated after each frame-by-frame optimization.
To ease fabrication, we provide a convenient workflow with tailored engineering tools and empirical fabrication guidance embedded in a standard CAD software, empowering regular users to design quad-robots. The modular design scheme allows the user to quickly start from a design template of the mechanical skeleton in
Related Work
Computational fabrication aims at designing and creating physical artifacts with the help of computational methods. A large class of methods addresses inverse design problems by incorporating fabrication limitations in geometric design algorithms via constrained optimization or the integration of fast simulation techniques [8], [9]. This line of research enables the design of objects with a wide range of controllable physical and mechanical properties, such as appearance [10], [11], [12], [13], deformation [14], [15], [16], [17], articulation [18], [19], [20], and mechanical motion [21], [22], [23], [24], [25]. Some existing contributions also investigated how to instantiate virtual characters as 3D-printable physical entities like mechanical robots [3], [21]. Yet, these methods merely focus on robots consisting of rigid links and basic balancing constraints and/or velocity limits.
Bickel et al. [26] proposed a process for designing synthetic skin and actuation parameters for animatronic characters that mimic facial expressions of a given subject. Skouras et al. [15] optimized the internal material distribution so that the resulting character exhibits the desired deformation behavior. Focusing on actuation, Bern et al. [27] computed the layout of winch-tendon networks to animate plush toys, and Ma et al. [28] optimized the chamber structure and material distribution for designing soft pneumatic objects.
Our work shares some of these goals but takes a significantly different approach. Instead of relying on a rigid or quasi-static underlying simulation of the skin deformation in our case, the influence of the soft skin on the embedded moving mechanical skeleton makes us face a dynamic two-way coupled multibody-elastic problem. It is much more challenging to accurately simulate and optimize due to the drastically increased system complexity, nonlinearity and discontinuity, i.e., due to the complimentary constraints enforced at the contact vertices.
Physics-based character motion generation has vast applications in both graphics and robotics. Algorithmic approaches include leveraging space-time optimization with necessary physical constraints and developing controllers to drive forward simulations.
The seminal work by Witkin and Kass [29] generated motion trajectories by optimizing physical constraints and animator controls at key frames, a well-known space-time constraints framework for animation. With proper motion data, the space-time optimization produces realistic articulated motions for bipedal or multilegged characters through different physical properties [30], [31], [32], [33], [34], [35], [36], [37], [38]. It can be used to transform motion capture data into physically plausible motions [39].
The locomotion controller aims to compute joint torques or control forces to drive the locomotion behaviors of articulated figures. The joint torques are usually calculated via the proportional and derivative (PD) controller such that the rigid skeleton of a character follows designated joint angle trajectories [40], [41], [42]. Balance control strategies, such as the swing foot placement or zero moment point, are essential to generating stable locomotions. [40], [41], [43], [44], [45], [46], [47], [48]. Continuous adaptation of the target joint trajectory for balancing a walking human was developed in [49]. Controllers that produce highly dynamic skills for human animation were suggested in [50], [51], [52]. The joint torques can also be computed via optimal control to approximate the motion capture data or motion data from kinematic simulators [53], [54].
Our work is inspired by studies on how to drive the soft skin deformation with the underyling rigid skeletons or pseudo muscle force [7], [55], [56]. Two-way coupling of rigid bodies and elastic bodies was considered in [57]. Fast simulation and control of soft robots of various configurations and actuations has also been studied using finite element method and the reduced formulation of compliance matrix [58], [59], [60], [61], [62]. The adjoint method is adopted to solve the space-time motion optimization problem for soft robots in two recent contributions [63], [64]. For the space-time motion constrained by the equation of motion, the adjoint method is efficient in computing the gradients of the motion with respect to control parameters. Since the method requires the constraints to be known ahead of the simulation, the contacts between the robot and the environment should be fixed as in [63] or approximated as a one-sided energy function in [64]. In contrast, our alternative optimization algorithm can handle dynamic contact points with LCP constraints, which is beneficial when the contacts need to be carefully modelled.
Elastic body simulation focuses on the formulation of an elastic deformation energy and the proper handling of contact constraints to simulate realistic deformations of soft bodies [65], [66], [67], [68]. A comprehensive survey of physics-based elastic deformation models can be found in [69].
Space-time optimization techniques can also be applied to control the motion of elastic bodies that are represented by volumetric meshes. To reduce the number of variables used to control the vertex positions in the optimization, model reduction techniques are frequently used [70], [71], [72]. Barbič et al. [70] imposed the equation of motion constraint in elastic body deformation, using the discrete adjoint method to compute the gradients of control forces. Pan et al. [73] integrated the contact forces as additional variables to handle environment interactions and solved the space-time objective with alternating optimization, but did not handle the two-way coupling problem we want to solve.
Overview
Given an input surface mesh of a quad-robot, we first design mechanical skeleton and skin mesh (Section 6.1) for the robot, and then use the proposed two-step alternating algorithm to optimize for a physically plausible motion plan (Section 5). The overall system flowchart is illustrated in Fig. 1.
We propose a computational fabrication system for designing and fabricating skinned quad-robots. Given an input mesh representing the shape of a quad-robot such as this beetle-like robot, we design its mechanical skeleton with motors to drive its locomotion. The motion plan is generated by an optimization algorithm with kinematic trajectories as the user input. The trajectories consist of the foot swing trajectories (red curves), center of mass (COM) trajectory (blue curve) and foot contact plan (yellow bars) input by the user. Our optimization fully takes account of all the physical and dynamical constraints. By fabricating this robot design, it can be verified that our algorithm is able to generate plausible and physically feasible motion plans for quad-robots, and the simulated results well match the physical experimental results. Note that we only render the transparent input surface without thickness to demonstrate the surface-structure coupling geometry.
During the alternating optimization, the first space-time optimization step outputs joint angle trajectories for the design according to the user-specified end-effector and COM trajectories (Section 5.1). This step is made possible by only considering the approximated skin deformation. The second frame-by-frame optimization step improves the physical plausibility of the joint angle trajectories with full simulation and various physical constraints(Section 5.2), such as physical torque limits for the selected motors in the design. Two-way coupled multibody-elastic dynamics (Section 4) are adopted in this step for the full simulation.
Finally, the designed robot is fabricated by fast prototyping methods for a physical validation (Section 6.2), and stepper motors are mounted to drive the skeleton and the attached soft skin to realize the motion plan.
Two-way Coupled Multibody-Elastic Dynamics
A core ingredient of our system is the dynamic simulation of the robot using a self-actuated rigid skeleton with a soft skin attached. We are inspired by existing coupled simulation systems in graphics [74], [75], [76] and exploit the Lagrange multipliers method to enforce the two-way coupling between the skeleton and the soft skin, which can be naturally integrated into the subsequent locomotion optimization. The Lagrange multipliers are used to guarantee that the skeleton and skin are attached to each other at prescribed locations, and we solve for all the unknown DOFs from both subsystems simultaneously.
4.1 Two-Way Skeleton-Skin Coupling
We use Lagrangian mechanics for both the rigid skeleton and soft skin and obtain a symmetric formulation for these two subsystems. To ease the formulation of motion contraints, we use the generalized coordinates
The two subsystems are coupled by attaching the soft skin to the underlying skeleton at prescribed glue vertices. Mathematically, this straightforward treatment leads to a set of nonlinear position constraints:
\begin{equation*}
\mathscr {C}(\mathbf {q},\mathbf {u})=\mathscr {R}(\mathbf {q})\mathbf {r}+\mathbf {t}-\mathbf {x}_c=0. \tag{1}
\end{equation*}
Using the Lagrange multipliers method, we obtain the coupled multibody-elastic system:
\begin{equation*}
\begin{bmatrix}\mathbf {A}_r & \mathbf {0} & \nabla _q\mathscr {C}^\top \\
\mathbf {0} & \mathbf {A}_d & \nabla _u\mathscr {C}^\top \\
\nabla _q\mathscr {C} & \nabla _u\mathscr {C} & \mathbf {0} \end{bmatrix} \begin{bmatrix}\Delta \mathbf {q}\\
\Delta \mathbf {u}\\
\pmb {\lambda }\end{bmatrix} = \begin{bmatrix}\mathbf {b}_r\\
\mathbf {b}_d\\
\mathbf {0} \end{bmatrix}. \tag{2}
\end{equation*}
4.2 Collision and Contact Handling
There are two types of collisions/contacts we need to take care of in our simulation. The first is the collision between the robot’s feet and the ground surface, which provides necessary support and friction forces to the robot. As will be detailed in Section 5.2, we resolve them using linear complementary constraints (LCP) to guarantee the physical feasibility of the locomotion.
The second is the self-collision of the soft skin; rotating joints tend to compress the inward skin and induce self-collisions. Moreover, skin-skeleton collisions1 could also occur when the skeleton is being articulated. Because such collisions typically take place under low relative velocities, we handle them using the explicit penalty force method [79], [80].
Motion Plan Optimization
As the system input, the trajectories of the COM, end effectors, and the footfall pattern are provided by the user. Our system generates a dynamically feasible motion plan for the robot that resembles as much as possible the one prescribed by the user. A motion plan, defined as
Previous works, e.g., [Megaro et al. 15], solved the motion design problem by simultaneously finding the optimal skeleton configuration for all the frames in
5.1 Space-Time Optimization With Skin Deformation Approximation
Similar to the formulation in [36], for each
Given these quantities, the optimization objective is defined as the weighted sum of six terms that balance the user-specified end effector and COM trajectories and the smoothness of the optimized motion:
\begin{equation*}
E_A = \min \sum _i\left(\alpha _tE_{\pmb {\tau }}^i+\alpha _sE_S^i+\alpha _cE_{COM}^i+\alpha _eE_{EE}^i+\alpha _fE_F^i+\alpha _oE_O^i\right).\
\tag{3}
\end{equation*}
\begin{equation*}
\displaystyle E_{\pmb {\tau }}^i = {\frac{1}{m}}^2\left\Vert \pmb {\tau }^i(\mathbf {q}^i, \pmb {\lambda }^i, \mathcal {F}^i_c, \pmb {\tau }^i_c)\right\Vert ^2.
\end{equation*}
The second term
\begin{equation*}
E_{S}^i = \left\Vert \mathbf {q}^{i+1} - 2\mathbf {q}^{i}+\mathbf {q}^{i-1}\right\Vert ^2.
\end{equation*}
The two terms,
\begin{equation*}
\displaystyle E_{EE}^i = \left\Vert \phi _{EE}^i(\mathbf {q}^i,\mathbf {u}^i) - \mathbf {e}^i\right\Vert ^2,\quad \displaystyle E_{COM}^i = \left\Vert \phi ^i_{COM}(\mathbf {q}^i,\mathbf {u}^i) - \mathbf {g}_i\right\Vert ^2,
\end{equation*}
The term
\begin{equation*}
E_F^i = \left\Vert \mathbf {q}^i - \tilde{\mathbf {q}}^i\right\Vert ^2.
\end{equation*}
The last term
\begin{equation*}
\displaystyle E_{O}^i = \left\Vert \psi ^i_{EE}(\mathbf {q}^i) - \hat{\mathbf {n}}\right\Vert ^2,
\end{equation*}
We also impose hard kinematic and dynamic constraints on the optimized variables to obtain a stable motion plan. The kinematic constraints include the contact constraint, the center of pressure (COP) constraint and the optional periodic constraint, while the dynamic constraints include the momentum and the friction force constraints as in [36].
Contact Constraint. In the optimization, we need to enforce the footfall pattern that is specified by the user to encode when the foot should leave or touch the ground. This constraint can be written into:
\begin{align*}
& \displaystyle c^i_j{\phi _{EE,j}^i(\mathbf {q}^i,\mathbf {u}^i)}_y=0,\qquad \qquad \qquad \qquad \qquad \qquad \qquad \forall i,j, \\
& \displaystyle c^{i-1}_jc^i_j(\phi _{EE,j}^{i}(\mathbf {q}^i,\mathbf {u}^i) - \phi _{EE,j}^{i-1}(\mathbf {q}^i,\mathbf {u}^i)) = 0,\qquad \qquad \qquad \forall i,j, \tag{4}
\end{align*}
COP Constraint. The COP should be inside the supporting polygon for a stable motion plan. This constraint can be written into:
\begin{equation*}
\displaystyle \mathbf {P}\cdot \phi ^i_{COP} \leq \mathbf {0}, \qquad \forall i, \tag{5}
\end{equation*}
where the funtion
Periodic Constraint. When the user desires a periodic motion, the joint angles are expected to be the same in the first and the last frame of the optimized motion plan:
\begin{equation*}
J(q^1) = J(q^N), \tag{6}
\end{equation*}
Momentum Constraint. The change of the linear and angular momentum of the robot should be determined by the external contact forces and torques, which can be formulated into the following equations:
\begin{align*}
& \displaystyle \dot{\mathbf {R}}^i = mg + \sum _jc^i_j\mathcal {F}^i_{c,j}, \qquad \qquad \qquad \qquad \qquad \qquad \;\;\quad \forall i,j, \\
& \displaystyle \dot{\mathbf {L}}^i = \sum _j c^i_j\left(\left(\mathbf {p}_{c,j}^i - \phi ^i_{COM}(\mathbf {q}^i,\mathbf {u}^i)\right)\times \mathcal {F}^i_{c,j}+ \pmb {\tau }_{c,j}^i\right), \qquad \forall i,j, \tag{7}
\end{align*}
Friction Force Constraint. The contact force should be inside the friction cone to satisfy the Coulomb model of friction. Specifically, we have:
\begin{align*}
& \displaystyle \frac{1}{m}(\mu {\mathcal {F}^i_{c,j}}_\perp - \Vert {\mathcal {F}^i_{c,j}}_{\Vert }\Vert) \geq 0, \qquad \qquad \qquad \qquad \forall c^i_j=1, \\
& \displaystyle \frac{1}{m}^2(\Vert {\mathcal {F}^i_{c,j}}\Vert ^2 - \Vert \frac{{\pmb {\tau }^i_j}_{\Vert }}{\nu _b}\Vert ^2 - \frac{{\pmb {\tau }^i_j}_{\perp }}{\nu _t}^2) \geq 0, \qquad \qquad \quad \forall c^i_j=1, \tag{8}
\end{align*}
Optimization. With the defined objective function and constraints, the space-time optimization step can be written into:
\begin{align*}
& \min _{\mathbf {q}^i,\mathcal {F}^i_{c,j}, \pmb {\tau }^i_c,j, i=1,..N} \qquad E_A \\
& \text{st.}: \
\boldsymbol{\phi}_e = 0, \boldsymbol{\phi}_g \leq 0, \tag{9}
\end{align*}
5.2 Frame-by-Frame Optimization With Full Dynamics
In the frame-by-frame optimization, we drop the simplification of the previous step and consider the full dynamics formulated in Eq. (2) in a similar way as in [7]. This allows us to further improve the physical plausibility of the motion. In practice, this requires the solution of a difficult quadratic programming problem with complementarity constraints (QPCC) to handle contact and friction. Different to the soft body only formulation in [7], the coupling constraints between multi-body skeletion and elastic skin introduce a large number of Lagrange multiplier variables and largely increase the complexity of the solver. To speed up the solution, we follow the condensation technique widely used in physical simulation [81], [82]. Specifically, we select the driving torques at joints and foot contact forces as optimization variables and lump the DOFs of mesh vertices and rigid skeletons to these variables through the condensation of the system matrix in Eq. (2). This choice facilitates the formulation of the physical torque limit constraints of motors as well. In this section, we describe the details of the matrix condensation and the per-frame optimization problem.
System Matrix Condensation. With the coupled multibody-elastic system defined in Eq. (2), the nonlinear relation between the simulated DOFs
\begin{align*}
\Delta \mathbf {u}=\mathbf {A}_d^{-1}\mathbf {b}_d-\mathbf {A}_d^{-1}\nabla _u\mathscr{C}^\top \mathbf {A}_C^{-1}\left(\nabla _q\mathscr {C}\mathbf {A}_r^{-1}\mathbf {b}_r+\nabla _u\mathscr {C}\mathbf {A}_d^{-1}\mathbf {b}_d\right), \\
\Delta \mathbf {q}=\mathbf {A}_r^{-1}\mathbf {b}_r-\mathbf {A}_r^{-1}\nabla _q\mathscr {C}^\top \mathbf {A}_C^{-1}\left(\nabla _q\mathscr {C}\mathbf {A}_r^{-1}\mathbf {b}_r+\nabla _u\mathscr {C}\mathbf {A}_d^{-1}\mathbf {b}_d\right), \tag{10}
\end{align*}
According to the formulation of
\begin{equation*}
\Delta \mathbf {q}=\phi _{\Delta \mathbf {q}}\big (\pmb {\tau },\mathcal {F}_{\perp },\mathcal {F}_{\Vert }\big),\quad \text{and}\quad \Delta \mathbf {u}=\phi _{\Delta \mathbf {u}}\big (\pmb {\tau },\mathcal {F}_{\perp },\mathcal {F}_{\Vert }\big). \tag{11}
\end{equation*}
Given
Optimization. We follow the control strategy used in [7] to optimize the input motion plan on a frame-by-frame basis. It is used to make sure that the output joint angle trajectories of the space-time optimization step are physically feasible, which is achieved using the two-way coupled multibody-elastic dynamics as constraints. At each frame, it can be formulated as a quadratic programming problem with complementarity constraints.
Specifically, we seek for joint torques (
\begin{align*}
& \displaystyle \min _{\pmb {\tau }^i,\mathcal {F}_{\perp }^i,\mathcal {F}_{\Vert }^i,\pmb {\lambda }_{\Vert }^i} E_G\left(\pmb {\tau }^i,\mathcal {F}^i_{\perp },\mathcal {F}^i_{\Vert }\right) & \\
& \displaystyle \text{subject to:} \\
& \displaystyle \Vert \pmb {\tau }^i_m\Vert < U_m, m = 1,\ldots,M \\
& \displaystyle \mathbf {P}\cdot \phi ^i_{COP}(\pmb {\tau }^i,\mathcal {F}_{\perp }^i,\mathcal {F}_{\Vert }^i) \leq \mathbf {0} \\
& \displaystyle \mathbf {0} \leq \begin{bmatrix}\mathcal {F}^i_{\perp } \\
\mathcal {F}^i_{\Vert } \\
\lambda ^i_{\Vert } \end{bmatrix} \perp \begin{bmatrix}\displaystyle \hat{\mathbf {n}}^\top \frac{\Delta \mathbf {u}_c^i}{\Delta t} \\
\displaystyle \mathbf {D}^{\top }\frac{\Delta \mathbf {u}_c^i}{\Delta t} + \displaystyle \mathbf {1}\lambda _{\Vert }\\
\mu \mathcal {F}^i_{\perp } - \mathbf {1}^{\top }\mathcal {F}^i_{\Vert } \end{bmatrix} \geq \mathbf {0}. \tag{12}
\end{align*}
In Eq. (12), the first hard inequality constraint of
The objective function
\begin{equation*}
E_G= \alpha _S E_S + \alpha _F E_F + \alpha _{O} E_{O} + \alpha _{\pmb {\tau }}E_{\pmb {\tau }} +\alpha _C E_C, \tag{13}
\end{equation*}
\begin{align*}
& \displaystyle E_S = \left\Vert \phi ^i_{\Delta \mathbf {q}} - \phi ^{i-1}_{\Delta \mathbf {q}}\right\Vert ^2, \qquad \qquad \displaystyle E_F = \left\Vert \mathbf {q}^{i} + \phi ^i_{\Delta \mathbf {q}} - \bar{\mathbf {q}}^{i+1}\right\Vert ^2, \\
& \displaystyle E_{O} = \left\Vert \psi ^i_{EE} - \hat{\mathbf {n}}\right\Vert ^2, \qquad \qquad \displaystyle E_{\pmb {\tau }} = \left\Vert \pmb {\tau }_i - \pmb {\tau }_{i-1}\right|^2 \\
& \displaystyle E_{C} = \left\Vert \mathcal{E}\left(\phi _{EE}^i - \phi _{EE}^{i-1}\right)\right\Vert ^2. \tag{14}
\end{align*}
The first energy term
The contact forces are applied to the skin then affect the skeletal motion through the coupling. However, for the foot contacts between the robot and the ground, the contact forces are applied to the foot link using the soft contact method proposed in [55] for the fast response to the contacts and stable balance control. The computed contact forces applied at foot links are kept the same in the space-time optimization with a rigid-skeleton only.
5.3 Solving the QPCC
The key to solving the QPCC problem of Eq. (12) is to have a feasible configuration for all the contact vertices. Our strategy is similar to that of [7]: We flip complementary constraints when the inequality constraint reaches the boundary. Specifically, contact vertices fall into one of the three following categories:
Contact breakage means that the contact vertex will leave the ground plane in the next frame, and the complementary constraints should be lifted.
Sliding indicates that the contact vertex is moving within the ground plane. In this situation, the complementary constraint for its normal force
becomes:\mathcal {F}_{\perp } and the complementary constraints for the tangent force\begin{equation*} \mathcal {F}_{\perp } > 0,\quad \hat{\mathbf {n}}^\top \frac{\Delta \mathbf {u}_c^i}{\Delta t} = 0, \tag{15} \end{equation*} View Source\begin{equation*} \mathcal {F}_{\perp } > 0,\quad \hat{\mathbf {n}}^\top \frac{\Delta \mathbf {u}_c^i}{\Delta t} = 0, \tag{15} \end{equation*}
are:\mathcal {F}_\parallel \begin{align*} \displaystyle \mathcal {F}_\parallel \geq \mathbf {0}, & \displaystyle \mathbf {D}^{\top }\frac{\Delta \mathbf {u}_c^i}{\Delta t} + \mathbf {1}\lambda _{\Vert } = \mathbf {0}; \\ \displaystyle \lambda _{\Vert } \geq 0, & \displaystyle \mu \mathcal {F}_{\perp } - \mathbf {1}^{\top }\mathcal {F}_{\Vert } = 0. \tag{16} \end{align*} View Source\begin{align*} \displaystyle \mathcal {F}_\parallel \geq \mathbf {0}, & \displaystyle \mathbf {D}^{\top }\frac{\Delta \mathbf {u}_c^i}{\Delta t} + \mathbf {1}\lambda _{\Vert } = \mathbf {0}; \\ \displaystyle \lambda _{\Vert } \geq 0, & \displaystyle \mu \mathcal {F}_{\perp } - \mathbf {1}^{\top }\mathcal {F}_{\Vert } = 0. \tag{16} \end{align*}
Static friction implies that the contact vertex is fixed on the contact plane. In this case, the complementary constraint for its normal force is the same as Eq. (15). The constraints for the tangent force are:
The inequality constraint of\begin{align*} \displaystyle \mathcal {F}_\parallel \geq \mathbf {0}, & \displaystyle \mathbf {D}^{\top }\frac{\Delta \mathbf {u}_c^i}{\Delta t} + \mathbf {1}\lambda _{\Vert } = \mathbf {0}; \\ \displaystyle \lambda _{\Vert } = 0, & \displaystyle \mu \mathcal {F}_{\perp } - \mathbf {1}^{\top }\mathcal {F}_{\Vert } \geq 0. \tag{17} \end{align*} View Source\begin{align*} \displaystyle \mathcal {F}_\parallel \geq \mathbf {0}, & \displaystyle \mathbf {D}^{\top }\frac{\Delta \mathbf {u}_c^i}{\Delta t} + \mathbf {1}\lambda _{\Vert } = \mathbf {0}; \\ \displaystyle \lambda _{\Vert } = 0, & \displaystyle \mu \mathcal {F}_{\perp } - \mathbf {1}^{\top }\mathcal {F}_{\Vert } \geq 0. \tag{17} \end{align*}
specifies the friction cone constraint in the case of static friction. d\mu \mathcal {F}_{\perp } - \mathbf {1}^{\top }\mathcal {F}_{\Vert } \geq 0
We begin solving Eq. (12) by assuming all the contact vertices are fixed, which simplifies the original problem to
\begin{align*}
& \displaystyle \min _{\pmb {\tau }^i,\pmb {\gamma }_c} E_G\left(\pmb {\tau }^i,\pmb {\gamma }_c\right) & \\
& \displaystyle \text{subject to:} \\
& \displaystyle \Vert \pmb {\tau }^i_m\Vert < U_m, m = 1,\ldots,M \\
& \displaystyle \mathbf {P}\cdot \phi ^i_{COP} \leq \mathbf {0} \\
& \displaystyle \left[\phi ^i_{\Delta \mathbf {u}}\right]_c=\mathbf {0}, \tag{18}
\end{align*}
\begin{equation*}
\gamma _{\perp } = \hat{\mathbf {n}}^\top \pmb {\gamma }_c,\quad \text{and}\quad \pmb {\gamma }_{\Vert } = \big (\mathbf {I}-\hat{\mathbf {n}}\hat{\mathbf {n}}^\top \big)\pmb {\gamma }_c. \tag{19}
\end{equation*}
Typical converging curves are plotted in Fig. 4, and we stop the optimization after 10 iterations. The convergence of the QPCC solver means that it finds the contact category of each contact point that leads to minimal energy. It tries to switch the contact category of a contact point in the direction of lower energy, but occasional increased energy can still be observed.
Our QPCC solver converges quickly in most cases. The left plot is the converging curve of a frame when the front left leg of the monster-like robot leaves the ground. The middle plot is the converging curve of a frame when this leg is in the air (i.e., other three feet are on the ground). The right plot is the converging curve of a frame when this leg hits ground again.
5.4 Initialization
Given the mechanical skeleton and the skin mesh of a robot, we first associate the mesh vertices to the links of the skeleton to obtain its skinning information. Hence, the mesh vertices can be deformed with the skeleton in the space-time optimization step, while the local coordinates of the vertices should be computed using their deformed positions and the local frame of the links at each frame. The initial motion plan are computed through the space-time optimization step without the trajectory following terms
Design and Fabrication
Designing and fabricating a quad-robot is a challenging task. We facilitate the design by using a set of mechanical skeleton templates, and narrow the gap between professional and regular users by creating several SolidWorks scripts. This allows even an inexperienced user to tweak high-level semantic parameters. Fig. 6 shows three built-in mechanical skeleton templates provided in our system for quad-robots. Each template is built of modularized CAD parts to ease the fabrication cost. The first one is the design used in the beetle-like robot, which consists of a torso structure and four limb structures. Their exploded views are detailed in the figure as well. The torso structure has four shoulder joints that connect to its four limbs. A microcontroller board sending trigger signals to the motors is mounted inside of the torso. The limb structure includes linkage parts of an upper leg, a lower leg, and a foot. On each limb, two uniaxial motors are mounted to provide necessary rotational freedoms at the knee and the ankle. The other two templates vary in different initial poses and foot link geometries.
In the following, we describe the details of the design pipeline and the fabrication procedure respectively.
6.1 Design and Editing of Mechanical Skeleton
The design starts with a given 3D model that corresponds to the appearance of the robot. Our system extracts an initial skeletal line using the mesh contraction method [84] as shown in Fig. 5. This skeleton is actually an approximation of the medial axis of the model, and it is used as a general guide for the follow-up template embedding and editing. We employed the modular design idea so that the user can edit the geometry of a template mechanical component to obtain a customized mechanical skeleton for quad-robots of various morphologies. To this end, several
Typically, given a new surface model of a quad-robot, we embed limbs first and then adjust the geometry of the torso to make sure it fits the exterior skin. Specifically, a global scale of the mechanical structure template and local rotations of the links are first performed so that the template can be inside the input surface mesh. Then, the user can select the start and end points of a link on the extracted skeletal line and trigger the designed script to edit the link geometry to match the specified length and adjust the width of the link. Finally, the bracing unit of the torso is generated in a similar way as the skin creation(the details follows shortly), and we dig out holes to reduce its weight, for instance, the bracing unit for the torso of the beetle-like robot shown in the first picture in the second row of Fig. 1.
Skin and Folding Regions Creation. The exterior skin of the robot is designed to be 8 mm thick at the foot and 4 mm thick at other parts by default, and it is created by the mesh hollow operation in
6.2 Fabrication
The mechanical structure of the robot is 3D printed with polypropylene-like stereolithography (SLA) resin, which is a widely used material for fabricating joints and low-friction moving parts. The exterior skin of the robot is made of a layer of soft rubbery material and fabricated via injection molding. To reduce the effort and cost of creating the skin molds, we fabricate the skin on a piece-by-piece basis: one limb has one skin piece, and the torso has two pieces as shown in Fig. 1 (Skin pieces). The skin-skeleton attachment is physically realized by another 3D printed bracing unit between the skin and the skeleton. This bracing unit is attached to each link on the skeleton and serves as a supporting structure between the rubbery skin and the mechanical skeleton (see Figs. 1 and 9). The purpose of this design is to expect that the friction between the skin and the printed parts can disable the relative motion between skin and skeleton at these parts, which is verified in the physical validation. We thus select the glue vertices in Fig. 9 according to the position of skin-skeleton attachment parts so that the coupling constraints can reflect this physical setting. The mass matrix and the inertia tensor of this bracing unit are integrated in our multibody subsystem dynamics. Finally, skin pieces are glued together after all skin pieces are installed using nonreactive PVA adhesive.
Motor Specification. We usually use the
Experimental Results
In this section, we report motion design results generated by our algorithm and two fabricated robots for the physical validation and then proceed to the torque limits and folding region experiments conducted on the beetle-like robot. A comparison to kinematic optimization only is also provided for this robot. The performance of our optimization algorithm depends on the number of vertices on the skin mesh, the number of glue vertices, and the number of joints of the mechanical skeleton. The frame interval
Three mechanical structure templates and the exploded views of the torso and limb structures of the first template.
With the assistance of the developed
We add folding regions to facilitate the stretching deformation of the skin. The template folding region is similar to gear teeth, and it is formed by a sweeping cut operation, that is, the CSG difference between the volume surrounded by the original skin surface and the volume formed by rotating the sweeping contour along a central axis.
Motion Design Results. Fig. 10 illustrates the simple foot lifting motions designed by our system for the beetle-like robot. These two motions, i.e., single-foot lifting and double-foot lifting, are also used to show the COP is constrained to be inside the support polygon with our optimization algorithm. Please see the accompanying video for the animation.
The foot lifting motion for the Beetle-like robot. (a) Single-foot lifting. (b) double-foot lifting. The green balls indicate the COP positions and gray lines the support polygons. Our optimization algorithm can constrain the COP to be inside the support polygon.
The embedded skeleton of the monster-like robot shown in Fig. 6 is designed using the third template. The weight of this robot is
We generate a trotting motion of 0.45 meter/second speed for the monster-like robot to demonstrate that our system can support fast motion. In this example, the trajectories of joint positions are labelled using the horse motion pictures photographed by Eadweard Muybridge, a famous photographer for his work on motions. The joint positions are mapped to a horse motion with the specified speed using the method in [85] and re-targeted to the skeleton of our monster. This initial kinematic motion (please see the accompanying video for the motion) is then optimized using our alternating motion optimization algorithm to turn it into a physically feasible motion.
We notice that the flight phase of the initial kinematic motion is not consistent with the foot contact plan. To be more specific, the time of the flighting phase is not enough for the monster to return back to the ground. Thus, the space-time optimization with physical constraints, especially the momentum constraint, is necessary to eliminate such inconsistency, which is critical to the success of the alternating optimization. Fig. 11 illustrates the effect of the COP optimization. The red balls indicate that the COP positions at two frames in the initialized trotting motion plan are outside of supporting polygon after the first space-time optimization that does not account for the deformation of the skin mesh. Thus, the frame-by-frame simulation fails to produce a stable trotting motion with its initially optimized motion plan, as shown in the second row of Fig. 13. The COP constraint is turned off to produce this failed example once this constraint can not be satisfied by the solver. After the second iteration, the COPs are moved into supporting polygons, as indicated by the green balls. A smooth trotting motion can then be generated as shown in the first row on the right of Fig. 13. The comparisons of the optimized joint angles and the
The effect of the COP constraints in the trotting motion plan. Red balls: The COP positions computed using the motion plan after initialization. Green balls: The COP positions optimized with the skin mesh deformation. The supporting polygons are in cyran.
The monster-like robot takes two different input foot trajectories, and our system computes natural and physically correct motions for both inputs.
Trotting motion for the monster-like robot. (a) Marked joint positions. The color of a dot indicates to which part of the horse skeleton it belongs, and the positions are mapped to our monster skeleton joint angles using the space-time optimization with only kinematic constraints. (b) The designed trotting motion with our alternating algorithm. (c) The unstable motion simulated by the frame-by-frame optimization when the skin deformation is not considered in the space-time optimization.
Another example is reported in Fig. 14. The mechanical skeleton of this robot is further edited based on the second template of Fig. 6. We lengthened the torso and shortened the limbs to fit this template into the input model (125 cm × 47 cm × 46 cm). Our system also produces plausible motion plans for this quad-robot.
The motion of a lizard-like robot. We edit the second template in Fig. 6 with
Physical Validation. We fabricate two robots to validate the physical feasibility of our algorithm. The dimension of the fabricated beetle-like robot shown in Fig. 1 is 47.62 cm length × 33.66 cm width × 37.29 cm height, and its skeleton weight and skin weight are 2.8 kg and 1.1 kg respectively. Its motion is designed to spread its feet on the ground to enlarge the supporting area. Another robot, cow-like robot, is designed to be similar to the monster robot, but with the modified 3D shape. Its dimension is 55.71 cm length × 22.86 cm width × 47.72 cm height, and its skeleton and skin weights are 4.3 kg and 1.65 kg respectively. Since the robot is much higher than the beetle-like robot and thinner in the width, the balance control of the robot is more difficult. To deal with this larger robot, we select the DS3218 servo motor (dimension: 44 mm length × 20 mm width × 64 mm height, Voltage 6.0V) with maximal torque 3.13 N
Torque Limit. The torque limit in the motion optimization (i.e., Eq. (12)) of the beetle-like robot is set as 1.96 N
Folding Regions. Adding folding regions to the robot’s skin is an effective fabrication artisanry to enable the robot assembly using off-the-shelf servo motors and lower the fabrication cost. To demonstrate its advantage, we compare the skin deformation under the joint rotation when the robot is attached to a regular soft skin and a folded skin. Both skins are fabricated using the same materials. It can be seen from Fig. 17 that rotating joints yield large stretching stress over the skin, which could easily go beyond the physical capacity of many commercial servo motors. In this test, we follow the aforementioned motor specification by setting the maximal torque to 1.96 N
VS. Kinematic-Only Optimization. In contrast to robots with only rigid mechanical skeletons, skinned robots exhibit a much more complicated dynamic behavior, which should be fully incorporated during the motion design. To illustrate the necessity of incorporating influences of the soft skin, we compare the motion plans generated using our method and the one by Megaro et al. [3]. Because the primary focus in [3] is to design robot creatures with only rigid links, Megaro and colleagues used a kinematic-based optimization strategy, which includes the trajectories of COM, COP, end effectors, and the footfall pattern. Based on the resulting motion plan, we compute the corresponding driving torques at joints using inverse dynamics. Specifically, the driving torques are computed by imposing another set of rotation constraints over the skeleton in Eq. (2) using the Lagrange multipliers method (with necessary complimentary constraints and inequality constraints to handle the ground contact and motor torque limit). The constrained joint rotation corresponds to the one obtained from the kinematic-based motion plan, and the multipliers represent required generalized constraint force, which are converted to joint torque via
Failure Case. While our system is stable in the generation of slow walking motion, we find the generation of fast trot motion is sensitive to the physical parameters. When the mass of the monster is increased to two times, its influence on the mass center cannot be balanced in the optimization and the COP constraint is violated in the space-time optimization result, possibly due to its conflict between the foot contact constraint. Hence, the frame-by-frame optimization will fail to produce a stable motion. Such situation might be handled through the integration of foot plan sampling step in [36].
The fabricated cow-like robot. The motion plan is generated according to the contact plan (yellow bars) shown on the second picture in the first row.
We plot the torque values of the optimized motion planning of the beetle-like robot. Orange curve: the torque curve at an ankle joint (at the orange box). Blue curve: the torque curve at a shoulder joint (at the orange box).
Adding folding regions significantly relieves the stretching stress over the skin. We program the motor at an ankle joint of the beetle-like robot to rotate
The motion plan generated by the kinematic-only optimization [3] leads to unstable walking sequences. Left: Selected frames. Right: The joint angle curves. Kinematic: the kinematic optimization result. Inverse dynamics: the simulation result by following the kinematic optimization result. Our: our optimization result. The large roll angles of the root link is due to the unstable pose using kinematic-only optimization. Please see the accompanying video for the full comparison.
Physical experiments show that kinematic-only optimization is not a feasible solution for skinned robots – there are noticeable back steps (highlighted with a red box) in a motion cycle as the driving torques, after damped by the skin deformation, are not strong enough to produce necessary normal contact forces. Please refer to the accompanied video for a clearer comparison.
The comparison of joint angle curves and COM positions. With skin weight: the curves are from the initial space-time optimization result with only skin weight. With skin deformation: curves from the space-time optimization result with skin deformation simulated by frame-by-frame optimization. COM Z: the
Conclusion and Future Work
In this paper, we have presented a fabrication-oriented motion planing algorithm and detailed design/fabrication procedures for personalized skinned quad-robots. The physical constraints, such as the equations of motion of the skinned robot and the motor constraints, are integrated into the motion planning such that the resulting motion plan is physically and dynamically feasible. The condensation formulation allows us to conveniently establish the nonlinear relationship between external forces and the target kinematic parameters of the locomotion and to reach a QPCC formulation for the motion design. Our experiments show that the system is able to assist regular users to obtain natural and smooth motions designed for skinned quad-robots.
In the future, we want to explore a gait synthesis algorithm to generate the motion plan from high-level parameters, such as velocity and turning angles. Combining captured gait data and optimization with dynamic constraints has the potential to significantly reduce users’ labor efforts of creating such motion planning. Currently, the coupling between the FEM simulation of the soft skin and the rigid body dynamics of the mechanical structure is not fast enough for a closed-loop control of skinned quad-robots. We want to explore model reduction or homogenization techniques to reduce the computational cost of FEM simulation and produce interactive feedback to control skinned robots online.
ACKNOWLEDGMENTS
The authors would like to thank anonymous reviewers for their constructive comments. Weiwei Xu is partially supported by Zhejiang Lab. Yin Yang is partially spported by NSF under Grant Nos. CHS 1845024 and 1717972. Weiwei Xu and Hujun Bao are supported by Fundamental Research Funds for the Central Universities. This project has received funding from the European Research Council (ERC) under the European Unions Horizon 2020 research and innovation programme (Grant agreement No 715767).