20 #ifndef __XBOT__IMUSENSOR__ 
   21 #define __XBOT__IMUSENSOR__ 
   24 #include <Eigen/Geometry> 
   32     typedef std::shared_ptr<ImuSensor> 
Ptr;
 
   33     typedef std::shared_ptr<const ImuSensor> 
ConstPtr;
 
   47     ImuSensor(urdf::LinkConstSharedPtr sensor_link, 
int sensor_id);
 
   89     void getImuData(Eigen::Quaterniond& orientation, 
 
   90                     Eigen::Vector3d& acceleration,
 
   91                     Eigen::Vector3d& angular_velocity) 
const;
 
  102                     Eigen::Vector3d& acceleration,
 
  103                     Eigen::Vector3d& angular_velocity) 
const;
 
  114     void setImuData(Eigen::Quaterniond& orientation, 
 
  115                     Eigen::Vector3d& acceleration,
 
  116                     Eigen::Vector3d& angular_velocity,
 
  130                     Eigen::Vector3d& acceleration,
 
  131                     Eigen::Vector3d& angular_velocity,
 
  141     Eigen::Matrix3d _orientation;
 
  142     Eigen::Vector3d _lin_acc, _angular_velocity;