OpenWalker Project
Documentation of the ROS Packages
angular_velocity.h
Go to the documentation of this file.
1 
34 #ifndef OPEN_WALKER_CORE_ANGULAR_VELOCITY_H
35 #define OPEN_WALKER_CORE_ANGULAR_VELOCITY_H
36 
38 
39 namespace ow_core
40 {
48 template <typename _Scalar>
50  public AngularVelocityRef<Eigen::Matrix<_Scalar,3,1> >
51 {
52 public:
53  typedef _Scalar Scalar;
54  typedef Eigen::Matrix<_Scalar,3,1> Derived;
56 
57 protected:
58  Derived data_;
59 
60 public:
65  Base(data_)
66  {
67  }
68 
73  AngularVelocity(const Scalar& x, const Scalar& y, const Scalar& z) :
74  data_(x,y,z),
75  Base(data_)
76  {
77  }
78 
85  template <typename OtherDerived>
86  AngularVelocity(const Eigen::EigenBase<OtherDerived>& other) :
87  data_(other),
88  Base(data_)
89  {
90  }
91 
95  using Base::operator=;
96 
97 };
98 
99 } // namespace ow_core
100 
101 #endif // OPEN_WALKER_CORE_ANGULAR_VELOCITY_H
The AngularVelocity class.
Definition: angular_velocity.h:49
AngularVelocity(const Eigen::EigenBase< OtherDerived > &other)
Copy constructor.
Definition: angular_velocity.h:86
Definition: angular_acceleration.h:39
AngularVelocity()
Default Constructor.
Definition: angular_velocity.h:64
AngularVelocity(const Scalar &x, const Scalar &y, const Scalar &z)
Assignment from Scalar values.
Definition: angular_velocity.h:73
The AngularVelocityRef class.
Definition: angular_velocity_ref.h:52