Moby
RigidBody.h
1 /****************************************************************************
2  * Copyright 2005 Evan Drumwright
3  * This library is distributed under the terms of the Apache V2.0
4  * License (obtainable from http://www.apache.org/licenses/LICENSE-2.0).
5  ****************************************************************************/
6 
7 #ifndef _RIGID_BODY_H
8 #define _RIGID_BODY_H
9 
10 #include <list>
11 #include <boost/shared_ptr.hpp>
12 #include <boost/foreach.hpp>
13 #include <boost/weak_ptr.hpp>
14 #include <Ravelin/Vector3d.h>
15 #include <Ravelin/MatrixNd.h>
16 #include <Ravelin/Pose3d.h>
17 #include <Ravelin/SForced.h>
18 #include <Ravelin/SVelocityd.h>
19 #include <Ravelin/SAcceld.h>
20 #include <Ravelin/LinAlgd.h>
21 #include <Ravelin/SpatialRBInertiad.h>
22 #include <Moby/Constants.h>
23 #include <Moby/CollisionGeometry.h>
24 #include <Moby/ControlledBody.h>
25 #include <Ravelin/RigidBodyd.h>
26 
27 namespace osg { class Node; }
28 
29 namespace Moby {
30 
31 class ArticulatedBody;
32 class CollisionGeometry;
33 
35 
43 class RigidBody : public virtual Ravelin::RigidBodyd, public virtual ControlledBody
44 {
45  friend class ArticulatedBody;
46  friend class RCArticulatedBody;
47  friend class MCArticulatedBody;
48  friend class TimeSteppingSimulator;
49  friend class Joint;
50 
51  public:
52  enum Compliance { eRigid, eCompliant};
53  RigidBody();
54  virtual ~RigidBody() {}
55 
56  virtual void set_visualization_data(osg::Node* vdata) { Visualizable::set_visualization_data(vdata); }
57 
58  virtual void load_from_xml(boost::shared_ptr<const XMLTree> node, std::map<std::string, BasePtr>& id_map);
59  virtual void save_to_xml(XMLTreePtr node, std::list<boost::shared_ptr<const Base> >& shared_objects) const;
60  bool is_child_link(boost::shared_ptr<const RigidBody> query) const;
61  bool is_descendant_link(boost::shared_ptr<const RigidBody> query) const;
64  virtual void prepare_to_calc_ode(Ravelin::SharedConstVectorNd& x, double t, double dt, void* data);
65  virtual void prepare_to_calc_ode_sustained_constraints(Ravelin::SharedConstVectorNd& x, double t, double dt, void* data) { prepare_to_calc_ode(x, t, dt, data); }
66  virtual void ode(double t, double dt, void* data, Ravelin::SharedVectorNd& dx);
67  virtual void set_articulated_body(boost::shared_ptr<ArticulatedBody> body);
68  virtual void set_inertia(const Ravelin::SpatialRBInertiad& J);
69  virtual void apply_generalized_impulse(const Ravelin::SharedVectorNd& gj);
70 
71  template <class OutputIterator>
72  OutputIterator get_parent_links(OutputIterator begin) const;
73 
74  template <class OutputIterator>
75  OutputIterator get_child_links(OutputIterator begin) const;
76 
78  std::list<CollisionGeometryPtr> geometries;
79 
81  Compliance compliance;
82 
83  private:
84  RigidBodyPtr get_parent_link(boost::shared_ptr<Ravelin::Jointd> j) const;
85  RigidBodyPtr get_child_link(boost::shared_ptr<Ravelin::Jointd> j) const;
86 
87 #ifdef USE_OSG
88  osg::Node * inertia_viz;
89 #endif
90 }; // end class
91 
92 std::ostream& operator<<(std::ostream&, RigidBody&);
93 
94 // incline inline functions
95 #include "RigidBody.inl"
96 
97 } // end namespace
98 
99 #endif
100 
Abstract class for articulated bodies.
Definition: ArticulatedBody.h:26
std::list< CollisionGeometryPtr > geometries
Collision geometries, if any, for this rigid body.
Definition: RigidBody.h:78
RigidBodyPtr get_parent_link() const
Gets the first parent link of this link; returns NULL if there is no parent.
Definition: RigidBody.cpp:457
virtual void set_inertia(const Ravelin::SpatialRBInertiad &J)
Sets the rigid body inertia for this body.
Definition: RigidBody.cpp:61
bool is_child_link(boost::shared_ptr< const RigidBody > query) const
Determines whether the given link is a child link of this.
Definition: RigidBody.cpp:442
Defines an articulated body for use with reduced-coordinate dynamics algorithms.
Definition: RCArticulatedBody.h:43
virtual void save_to_xml(XMLTreePtr node, std::list< boost::shared_ptr< const Base > > &shared_objects) const
Implements Base::save_to_xml()
Definition: RigidBody.cpp:372
Represents a single rigid body.
Definition: RigidBody.h:43
virtual void set_articulated_body(boost::shared_ptr< ArticulatedBody > body)
Sets the articulated body corresponding to this body.
Definition: RigidBody.cpp:539
virtual void prepare_to_calc_ode_sustained_constraints(Ravelin::SharedConstVectorNd &x, double t, double dt, void *data)
Prepares to compute the derivative of the body (sustained constraints)
Definition: RigidBody.h:65
An event-driven simulator.
Definition: TimeSteppingSimulator.h:27
JointPtr get_inner_joint_explicit() const
Gets the explicit inner joint of this link; returns NULL if there is no explicit inner joint...
Definition: RigidBody.cpp:469
boost::shared_ptr< RigidBody > RigidBodyPtr
Rigid body smart pointer.
Definition: Types.h:62
virtual void prepare_to_calc_ode(Ravelin::SharedConstVectorNd &x, double t, double dt, void *data)
Prepares to compute the ODE.
Definition: RigidBody.cpp:475
virtual void set_visualization_data(osg::Node *vdata)
Sets the visualization data from a node.
Definition: Visualizable.cpp:58
boost::shared_ptr< XMLTree > XMLTreePtr
XML tree smart pointer.
Definition: Types.h:104
boost::shared_ptr< Joint > JointPtr
Reduced-coordinate articulated body joint smart pointer.
Definition: Types.h:74
bool is_descendant_link(boost::shared_ptr< const RigidBody > query) const
Determines whether the given link is a descendant of this.
Definition: RigidBody.cpp:451
virtual void ode(double t, double dt, void *data, Ravelin::SharedVectorNd &dx)
Computes the ODE.
Definition: RigidBody.cpp:515
Defines a joint used in articulated rigid body dynamics simulation.
Definition: Joint.h:30
RigidBody()
Default constructor.
Definition: RigidBody.cpp:47
Compliance compliance
Compliance value, determines event type.
Definition: RigidBody.h:81
virtual void apply_generalized_impulse(const Ravelin::SharedVectorNd &gj)
Applies a generalized impulse to the rigid body (calls the simulator)
Definition: RigidBody.cpp:54
Superclass for controlled bodies.
Definition: ControlledBody.h:21
virtual void set_visualization_data(osg::Node *vdata)
Sets the visualization data from a node.
Definition: RigidBody.h:56
virtual void load_from_xml(boost::shared_ptr< const XMLTree > node, std::map< std::string, BasePtr > &id_map)
Implements Base::load_from_xml()
Definition: RigidBody.cpp:132