XBotInterface  2.4.1
XBotInterface provides a generic API to model and control a robot.
ImuSensor.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 IIT-ADVR
3  * Author: Arturo Laurenzi, Luca Muratore
4  * email: arturo.laurenzi@iit.it, luca.muratore@iit.it
5  *
6  * This program is free software: you can redistribute it and/or modify
7  * it under the terms of the GNU Lesser General Public License as published by
8  * the Free Software Foundation, either version 3 of the License, or
9  * (at your option) any later version.
10  *
11  * This program is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU Lesser General Public License for more details.
15  *
16  * You should have received a copy of the GNU Lesser General Public License
17  * along with this program. If not, see <http://www.gnu.org/licenses/>
18 */
19 
20 #ifndef __XBOT__IMUSENSOR__
21 #define __XBOT__IMUSENSOR__
22 
24 #include <Eigen/Geometry>
25 
26 namespace XBot {
27 
28 class ImuSensor : public GenericSensor {
29 
30 public:
31 
32  typedef std::shared_ptr<ImuSensor> Ptr;
33  typedef std::shared_ptr<const ImuSensor> ConstPtr;
34 
39  ImuSensor();
40 
47  ImuSensor(urdf::LinkConstSharedPtr sensor_link, int sensor_id);
48 
55  void getOrientation(Eigen::Quaterniond& orientation) const;
56 
63  void getOrientation(Eigen::Matrix3d& orientation) const;
64 
71  void getLinearAcceleration(Eigen::Vector3d& acceleration) const;
72 
79  void getAngularVelocity(Eigen::Vector3d& angular_velocity) const;
80 
89  void getImuData(Eigen::Quaterniond& orientation,
90  Eigen::Vector3d& acceleration,
91  Eigen::Vector3d& angular_velocity) const;
92 
101  void getImuData(Eigen::Matrix3d& orientation,
102  Eigen::Vector3d& acceleration,
103  Eigen::Vector3d& angular_velocity) const;
104 
114  void setImuData(Eigen::Quaterniond& orientation,
115  Eigen::Vector3d& acceleration,
116  Eigen::Vector3d& angular_velocity,
117  double timestamp
118  );
119 
129  void setImuData(Eigen::Matrix3d& orientation,
130  Eigen::Vector3d& acceleration,
131  Eigen::Vector3d& angular_velocity,
132  double timestamp
133  );
134 
135  friend std::ostream& operator<< ( std::ostream& os, const XBot::ImuSensor& j );
136 
137 protected:
138 
139 private:
140 
141  Eigen::Matrix3d _orientation;
142  Eigen::Vector3d _lin_acc, _angular_velocity;
143 
144 
145 
146 
147 };
148 
149 }
150 
151 #endif
XBot::ImuSensor::ImuSensor
ImuSensor()
Default constructor.
Definition: ImuSensor.cpp:24
XBot::ImuSensor::getLinearAcceleration
void getLinearAcceleration(Eigen::Vector3d &acceleration) const
Getter for the IMU linear acceleration.
Definition: ImuSensor.cpp:62
XBot::GenericSensor
Generic sensor abstraction.
Definition: GenericSensor.h:36
XBot::ImuSensor::getOrientation
void getOrientation(Eigen::Quaterniond &orientation) const
Getter for the IMU orientation as a quaternion.
Definition: ImuSensor.cpp:72
GenericSensor.h
XBot::ImuSensor::getImuData
void getImuData(Eigen::Quaterniond &orientation, Eigen::Vector3d &acceleration, Eigen::Vector3d &angular_velocity) const
Getter for the IMU data i.e.
Definition: ImuSensor.cpp:53
XBot::ImuSensor::getAngularVelocity
void getAngularVelocity(Eigen::Vector3d &angular_velocity) const
Getter for the IMU angular velocity.
Definition: ImuSensor.cpp:39
XBot::ImuSensor
Definition: ImuSensor.h:28
XBot::ImuSensor::setImuData
void setImuData(Eigen::Quaterniond &orientation, Eigen::Vector3d &acceleration, Eigen::Vector3d &angular_velocity, double timestamp)
Setter for the IMU data i.e.
Definition: ImuSensor.cpp:89
XBot::ImuSensor::ConstPtr
std::shared_ptr< const ImuSensor > ConstPtr
Definition: ImuSensor.h:33
XBot::ImuSensor::Ptr
std::shared_ptr< ImuSensor > Ptr
Definition: ImuSensor.h:32
XBot
Definition: IXBotModel.h:20
XBot::ImuSensor::operator<<
friend std::ostream & operator<<(std::ostream &os, const XBot::ImuSensor &j)
Definition: ImuSensor.cpp:101