-
Notifications
You must be signed in to change notification settings - Fork 13
Constructing models
jhshannon17 edited this page Jan 31, 2015
·
7 revisions
- To set from primitives in XML use InertiaFromPrimitive:
<RigidBody id="box" enabled="true" position="0 .5000 0" angular-velocity="0 10.00 0" visualization-id="b1" linear-velocity="0 0 0">
<InertiaFromPrimitive primitive-id="b1" />
</RigidBody>
- To do this in code, set the mass of your primitive, then use set_inertia, passing the inertia of your primitive
Moby::PrimitivePtr box_prim(new Moby::BoxPrimitive(1, 1, 1));
box_prim->set_mass(10);
Moby::RigidBodyPtr box(new Moby::RigidBody());
box->set_inertia(box_prim->get_inertia());
- Set geometries for collision from a primitive with CollisionGeometry
<RigidBody id="box" enabled="true" position="0 .5000 0" angular-velocity="0 10.00 0" visualization-id="b1" linear-velocity="0 0 0">
<InertiaFromPrimitive primitive-id="b1" />
<CollisionGeometry primitive-id="b1" />
</RigidBody>
- Do this in code with a CollisionGeometry object, taking the geometry from a primitive
Moby::CollisionGeometryPtr box1CG(new Moby::CollisionGeometry());
box1CG->set_single_body(box); //box is the RigidBody
box1CG->set_geometry(box_prim1);
- Can do this from primitives using visualization-id
<RigidBody id="box" enabled="true" position="0 .5000 0" angular-velocity="0 10.00 0" visualization-id="b1" linear-velocity="0 0 0">
</RigidBody>
- If you wish to use a more sophisticated geometry than what comes from a primitive, specify that with vvisualization-filename
<RigidBody name="ground" id="ground" enabled="false" vvisualization-filename="ground.wrl" position="0 -.25 0">
</RigidBody>
- You can also do this in code from primitives
Moby::PrimitivePtr box_prim1(new Moby::BoxPrimitive(1, 1, 1));
Moby::RigidBodyPtr box(new Moby::RigidBody());
box->set_visualization_data(box_prim1->create_visualization());
- Example syntax for an articulated body model
<RCArticulatedBody id="FEEDER" floating-base="false" fdyn-algorithm="crb"
fdyn-algorithm-frame="link" rotate="0.0 0.05 0.0" translate="0.45,0,0" >
</RCArticulatedBody>
- The floating-base parameter indicates whether the base is affixed to the environment or "floating"
- Setup each link like a rigid body
<RCArticulatedBody id="FEEDER" floating-base="false" fdyn-algorithm="crb"
fdyn-algorithm-frame="link" rotate="0.0 0.05 0.0" translate="0.45,0,0" >
<RigidBody id="BASE" color="0 0 0 0" position="0 0 -0.02" angular-velocity="0 0 0" linear-velocity="0 0 0" visualization-id="base" compliant="false">
</RigidBody>
<!-- the body -->
<RigidBody id="SLIDE1" color="0 0 0 0" position="0 0 0" angular-velocity="0 0 0" linear-velocity="0 0 0" visualization-id="slide1-viz" compliant="false">
<CollisionGeometry primitive-id="slide1" />
<InertiaFromPrimitive primitive-id="slide1-viz" />
</RigidBody>
<RigidBody id="SLIDE2" color="0 0.5 0 1" position="0 0.055 0.01" angular-velocity="0 0 0" linear-velocity="0 0 0" visualization-id="slide2-viz" compliant="false">
<CollisionGeometry primitive-id="slide2" />
<InertiaFromPrimitive primitive-id="slide2-viz" />
</RigidBody>
<!-- ...full example in Moby/example/parts-feeder/feeder.xml... -->
</RCArticulatedBody>
- Setup body kinematics (set where each joint is located and its axis/axes)
<RCArticulatedBody id="FEEDER" floating-base="false" fdyn-algorithm="crb"
fdyn-algorithm-frame="link" rotate="0.0 0.05 0.0" translate="0.45,0,0" >
<RigidBody id="BASE" color="0 0 0 0" position="0 0 -0.02" angular-velocity="0 0 0" linear-velocity="0 0 0" visualization-id="base" compliant="false">
</RigidBody>
<PrismaticJoint id="shaker" location="0 0 0" inboard-link-id="BASE" outboard-link-id="SLIDE1" axis="1 0 0"/>
<!-- the body -->
<RigidBody id="SLIDE1" color="0 0 0 0" position="0 0 0" angular-velocity="0 0 0" linear-velocity="0 0 0" visualization-id="slide1-viz" compliant="false">
<CollisionGeometry primitive-id="slide1" />
<InertiaFromPrimitive primitive-id="slide1-viz" />
</RigidBody>
<FixedJoint id="fj1" location="0 0 0" inboard-link-id="SLIDE1" outboard-link-id="SLIDE2" />
<RigidBody id="SLIDE2" color="0 0.5 0 1" position="0 0.055 0.01" angular-velocity="0 0 0" linear-velocity="0 0 0" visualization-id="slide2-viz" compliant="false">
<CollisionGeometry primitive-id="slide2" />
<InertiaFromPrimitive primitive-id="slide2-viz" />
</RigidBody>
<!-- ...full example in Moby/example/parts-feeder/feeder.xml... -->
</RCArticulatedBody>