-
Notifications
You must be signed in to change notification settings - Fork 49
/
rigidbody.html
12 lines (12 loc) · 15.7 KB
/
rigidbody.html
1
2
3
4
5
6
7
8
9
10
11
12
<!DOCTYPE html>
<html lang="en"><head><meta charset="UTF-8"/><meta name="viewport" content="width=device-width, initial-scale=1.0"/><title>Rigid bodies · RigidBodyDynamics.jl</title><link href="https://cdnjs.cloudflare.com/ajax/libs/normalize/4.2.0/normalize.min.css" rel="stylesheet" type="text/css"/><link href="https://fonts.googleapis.com/css?family=Lato|Roboto+Mono" rel="stylesheet" type="text/css"/><link href="https://cdnjs.cloudflare.com/ajax/libs/font-awesome/4.6.3/css/font-awesome.min.css" rel="stylesheet" type="text/css"/><link href="https://cdnjs.cloudflare.com/ajax/libs/highlight.js/9.12.0/styles/default.min.css" rel="stylesheet" type="text/css"/><script>documenterBaseURL="."</script><script src="https://cdnjs.cloudflare.com/ajax/libs/require.js/2.2.0/require.min.js" data-main="assets/documenter.js"></script><script src="siteinfo.js"></script><script src="../versions.js"></script><link href="assets/documenter.css" rel="stylesheet" type="text/css"/></head><body><nav class="toc"><h1>RigidBodyDynamics.jl</h1><select id="version-selector" onChange="window.location.href=this.value" style="visibility: hidden"></select><form class="search" id="search-form" action="search.html"><input id="search-query" name="q" type="text" placeholder="Search docs"/></form><ul><li><a class="toctext" href="index.html">Home</a></li><li><a class="toctext" href="quickstart.html">Quick start guide</a></li><li><a class="toctext" href="spatial.html">Spatial vector algebra</a></li><li><a class="toctext" href="joints.html">Joints</a></li><li class="current"><a class="toctext" href="rigidbody.html">Rigid bodies</a><ul class="internal"><li><a class="toctext" href="#Index-1">Index</a></li><li><a class="toctext" href="#The-RigidBody-type-1">The <code>RigidBody</code> type</a></li><li><a class="toctext" href="#Functions-1">Functions</a></li></ul></li><li><a class="toctext" href="mechanism.html">Mechanism</a></li><li><a class="toctext" href="mechanismstate.html">MechanismState</a></li><li><a class="toctext" href="algorithms.html">Kinematics/dynamics algorithms</a></li><li><a class="toctext" href="customcollections.html">Custom collection types</a></li><li><a class="toctext" href="caches.html">Cache types</a></li><li><a class="toctext" href="simulation.html">Simulation</a></li><li><a class="toctext" href="benchmarks.html">Benchmarks</a></li></ul></nav><article id="docs"><header><nav><ul><li><a href="rigidbody.html">Rigid bodies</a></li></ul><a class="edit-page" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/master/docs/src/rigidbody.md"><span class="fa"></span> Edit on GitHub</a></nav><hr/><div id="topbar"><span>Rigid bodies</span><a class="fa fa-bars" href="#"></a></div></header><h1><a class="nav-anchor" id="Rigid-bodies-1" href="#Rigid-bodies-1">Rigid bodies</a></h1><h2><a class="nav-anchor" id="Index-1" href="#Index-1">Index</a></h2><ul><li><a href="rigidbody.html#RigidBodyDynamics.RigidBody"><code>RigidBodyDynamics.RigidBody</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.add_contact_point!-Union{Tuple{T}, Tuple{RigidBody{T},ContactPoint{T,SoftContactModel{HuntCrossleyModel{T},ViscoelasticCoulombModel{T}}}}} where T"><code>RigidBodyDynamics.add_contact_point!</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.add_frame!-Tuple{RigidBody,Transform3D}"><code>RigidBodyDynamics.add_frame!</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.change_default_frame!-Tuple{RigidBody,CartesianFrame3D}"><code>RigidBodyDynamics.change_default_frame!</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.contact_points-Tuple{RigidBody}"><code>RigidBodyDynamics.contact_points</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.default_frame-Tuple{RigidBody}"><code>RigidBodyDynamics.default_frame</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.fixed_transform-Tuple{RigidBody,CartesianFrame3D,CartesianFrame3D}"><code>RigidBodyDynamics.fixed_transform</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.frame_definition-Tuple{RigidBody,CartesianFrame3D}"><code>RigidBodyDynamics.frame_definition</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.frame_definitions-Tuple{RigidBody}"><code>RigidBodyDynamics.frame_definitions</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.has_defined_inertia-Tuple{RigidBody}"><code>RigidBodyDynamics.has_defined_inertia</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.is_fixed_to_body-Tuple{RigidBody,CartesianFrame3D}"><code>RigidBodyDynamics.is_fixed_to_body</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.spatial_inertia-Union{Tuple{RigidBody{T}}, Tuple{T}} where T"><code>RigidBodyDynamics.spatial_inertia</code></a></li><li><a href="rigidbody.html#RigidBodyDynamics.spatial_inertia!-Tuple{RigidBody,SpatialInertia}"><code>RigidBodyDynamics.spatial_inertia!</code></a></li></ul><h2><a class="nav-anchor" id="The-RigidBody-type-1" href="#The-RigidBody-type-1">The <code>RigidBody</code> type</a></h2><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.RigidBody" href="#RigidBodyDynamics.RigidBody"><code>RigidBodyDynamics.RigidBody</code></a> — <span class="docstring-category">Type</span>.</div><div><div><pre><code class="language-julia">mutable struct RigidBody{T}</code></pre><p>A non-deformable body.</p><p>A <code>RigidBody</code> has inertia (represented as a <a href="spatial.html#RigidBodyDynamics.Spatial.SpatialInertia"><code>SpatialInertia</code></a>), unless it represents a root (world) body. A <code>RigidBody</code> additionally stores a list of definitions of coordinate systems that are rigidly attached to it.</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L3">source</a></section><h2><a class="nav-anchor" id="Functions-1" href="#Functions-1">Functions</a></h2><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.add_contact_point!-Union{Tuple{T}, Tuple{RigidBody{T},ContactPoint{T,SoftContactModel{HuntCrossleyModel{T},ViscoelasticCoulombModel{T}}}}} where T" href="#RigidBodyDynamics.add_contact_point!-Union{Tuple{T}, Tuple{RigidBody{T},ContactPoint{T,SoftContactModel{HuntCrossleyModel{T},ViscoelasticCoulombModel{T}}}}} where T"><code>RigidBodyDynamics.add_contact_point!</code></a> — <span class="docstring-category">Method</span>.</div><div><div><pre><code class="language-julia">add_contact_point!(body, point)
</code></pre><p>Add a new contact point to the rigid body</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L168">source</a></section><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.add_frame!-Tuple{RigidBody,Transform3D}" href="#RigidBodyDynamics.add_frame!-Tuple{RigidBody,Transform3D}"><code>RigidBodyDynamics.add_frame!</code></a> — <span class="docstring-category">Method</span>.</div><div><div><pre><code class="language-julia">add_frame!(body, transform)
</code></pre><p>Add a new frame definition to <code>body</code>, represented by a homogeneous transform from the <code>CartesianFrame3D</code> to be added to any other frame that is already attached to <code>body</code>.</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L130">source</a></section><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.contact_points-Tuple{RigidBody}" href="#RigidBodyDynamics.contact_points-Tuple{RigidBody}"><code>RigidBodyDynamics.contact_points</code></a> — <span class="docstring-category">Method</span>.</div><div><div><pre><code class="language-julia">contact_points(body)
</code></pre><p>Return the contact points attached to the body as an ordered collection.</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L181">source</a></section><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.default_frame-Tuple{RigidBody}" href="#RigidBodyDynamics.default_frame-Tuple{RigidBody}"><code>RigidBodyDynamics.default_frame</code></a> — <span class="docstring-category">Method</span>.</div><div><div><pre><code class="language-julia">default_frame(body)
</code></pre><p>The <a href="spatial.html#RigidBodyDynamics.Spatial.CartesianFrame3D"><code>CartesianFrame3D</code></a> with respect to which all other frames attached to <code>body</code> are defined.</p><p>See <a href="rigidbody.html#RigidBodyDynamics.frame_definitions-Tuple{RigidBody}"><code>frame_definitions(body)</code></a>, <a href="rigidbody.html#RigidBodyDynamics.frame_definition-Tuple{RigidBody,CartesianFrame3D}"><code>frame_definition(body, frame)</code></a>.</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L91">source</a></section><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.fixed_transform-Tuple{RigidBody,CartesianFrame3D,CartesianFrame3D}" href="#RigidBodyDynamics.fixed_transform-Tuple{RigidBody,CartesianFrame3D,CartesianFrame3D}"><code>RigidBodyDynamics.fixed_transform</code></a> — <span class="docstring-category">Method</span>.</div><div><div><pre><code class="language-julia">fixed_transform(body, from, to)
</code></pre><p>Return the transform from <code>CartesianFrame3D</code> <code>from</code> to <code>to</code>, both of which are rigidly attached to <code>body</code>.</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L116">source</a></section><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.has_defined_inertia-Tuple{RigidBody}" href="#RigidBodyDynamics.has_defined_inertia-Tuple{RigidBody}"><code>RigidBodyDynamics.has_defined_inertia</code></a> — <span class="docstring-category">Method</span>.</div><div><div><pre><code class="language-julia">has_defined_inertia(b)
</code></pre><p>Whether the body has a defined inertia.</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L50">source</a></section><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.spatial_inertia!-Tuple{RigidBody,SpatialInertia}" href="#RigidBodyDynamics.spatial_inertia!-Tuple{RigidBody,SpatialInertia}"><code>RigidBodyDynamics.spatial_inertia!</code></a> — <span class="docstring-category">Method</span>.</div><div><div><pre><code class="language-julia">spatial_inertia!(body, inertia)
</code></pre><p>Set the spatial inertia of the body.</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L65">source</a></section><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.spatial_inertia-Union{Tuple{RigidBody{T}}, Tuple{T}} where T" href="#RigidBodyDynamics.spatial_inertia-Union{Tuple{RigidBody{T}}, Tuple{T}} where T"><code>RigidBodyDynamics.spatial_inertia</code></a> — <span class="docstring-category">Method</span>.</div><div><div><p>Return the spatial inertia of the body. If the inertia is undefined, calling this method will result in an error.</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L57">source</a></section><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.change_default_frame!-Tuple{RigidBody,CartesianFrame3D}" href="#RigidBodyDynamics.change_default_frame!-Tuple{RigidBody,CartesianFrame3D}"><code>RigidBodyDynamics.change_default_frame!</code></a> — <span class="docstring-category">Method</span>.</div><div><div><pre><code class="language-julia">change_default_frame!(body, new_default_frame)
</code></pre><p>Change the default frame of <code>body</code> to <code>frame</code> (which should already be among <code>body</code>'s frame definitions).</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L149">source</a></section><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.frame_definition-Tuple{RigidBody,CartesianFrame3D}" href="#RigidBodyDynamics.frame_definition-Tuple{RigidBody,CartesianFrame3D}"><code>RigidBodyDynamics.frame_definition</code></a> — <span class="docstring-category">Method</span>.</div><div><div><pre><code class="language-julia">frame_definition(body, frame)
</code></pre><p>Return the <a href="spatial.html#RigidBodyDynamics.Spatial.Transform3D"><code>Transform3D</code></a> defining <code>frame</code> (attached to <code>body</code>) with respect to <a href="rigidbody.html#RigidBodyDynamics.default_frame-Tuple{RigidBody}"><code>default_frame(body)</code></a>.</p><p>Throws an error if <code>frame</code> is not attached to <code>body</code>.</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L101">source</a></section><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.frame_definitions-Tuple{RigidBody}" href="#RigidBodyDynamics.frame_definitions-Tuple{RigidBody}"><code>RigidBodyDynamics.frame_definitions</code></a> — <span class="docstring-category">Method</span>.</div><div><div><pre><code class="language-none">frame_definitions(body)</code></pre><p>Return the list of homogeneous transforms (<a href="spatial.html#RigidBodyDynamics.Spatial.Transform3D"><code>Transform3D</code></a>s) that define the coordinate systems attached to <code>body</code> with respect to a single common frame (<a href="rigidbody.html#RigidBodyDynamics.default_frame-Tuple{RigidBody}"><code>default_frame(body)</code></a>).</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L74-L80">source</a></section><section class="docstring"><div class="docstring-header"><a class="docstring-binding" id="RigidBodyDynamics.is_fixed_to_body-Tuple{RigidBody,CartesianFrame3D}" href="#RigidBodyDynamics.is_fixed_to_body-Tuple{RigidBody,CartesianFrame3D}"><code>RigidBodyDynamics.is_fixed_to_body</code></a> — <span class="docstring-category">Method</span>.</div><div><div><pre><code class="language-julia">is_fixed_to_body(body, frame)
</code></pre><p>Whether <code>frame</code> is attached to <code>body</code> (i.e. whether it is among <a href="rigidbody.html#RigidBodyDynamics.frame_definitions-Tuple{RigidBody}"><code>frame_definitions(body)</code></a>).</p></div></div><a class="source-link" target="_blank" href="https://github.com/JuliaRobotics/RigidBodyDynamics.jl/blob/76c23d59410d62be3d363142875ea9c8c1eea909/src/rigid_body.jl#L83">source</a></section><footer><hr/><a class="previous" href="joints.html"><span class="direction">Previous</span><span class="title">Joints</span></a><a class="next" href="mechanism.html"><span class="direction">Next</span><span class="title">Mechanism</span></a></footer></article></body></html>