imu_sensor_interface.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of hiDOF, Inc. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
29 
30 #ifndef HARDWARE_INTERFACE_IMU_SENSOR_INTERFACE_H
31 #define HARDWARE_INTERFACE_IMU_SENSOR_INTERFACE_H
32 
34 #include <string>
35 
36 namespace hardware_interface
37 {
38 
45 {
46 public:
47  struct Data
48  {
49  Data()
50  : name(),
51  frame_id(),
52  orientation(0),
58 
59  std::string name;
60  std::string frame_id;
61  double* orientation;
63  double* angular_velocity;
67  };
68 
69  ImuSensorHandle(const Data& data = Data())
70  : name_(data.name),
71  frame_id_(data.frame_id),
78  {}
79 
81  const std::string& name,
82  const std::string& frame_id,
83  const double* orientation,
84  const double* orientation_covariance,
85  const double* angular_velocity,
86  const double* angular_velocity_covariance,
87  const double* linear_acceleration,
88  const double* linear_acceleration_covariance
89  )
90  : name_(name),
91  frame_id_(frame_id),
92  orientation_(orientation),
93  orientation_covariance_(orientation_covariance),
94  angular_velocity_(angular_velocity),
95  angular_velocity_covariance_(angular_velocity_covariance),
96  linear_acceleration_(linear_acceleration),
97  linear_acceleration_covariance_(linear_acceleration_covariance)
98  {}
99 
100  std::string getName() const {return name_;}
101  std::string getFrameId() const {return frame_id_;}
102  const double* getOrientation() const {return orientation_;}
103  const double* getOrientationCovariance() const {return orientation_covariance_;}
104  const double* getAngularVelocity() const {return angular_velocity_;}
106  const double* getLinearAcceleration() const {return linear_acceleration_;}
108 
109 private:
110  std::string name_;
111  std::string frame_id_;
112 
113  const double* orientation_;
114  const double* orientation_covariance_;
115  const double* angular_velocity_;
117  const double* linear_acceleration_;
119 };
120 
122 class ImuSensorInterface : public HardwareResourceManager<ImuSensorHandle> {};
123 
124 }
125 
126 #endif // HARDWARE_INTERFACE_IMU_SENSOR_INTERFACE_H
double * angular_velocity_covariance
A pointer to the storage of the angular velocity covariance value: a row major 3x3 matrix about (x...
double * orientation
A pointer to the storage of the orientation value: a quaternion (x,y,z,w)
ImuSensorHandle(const Data &data=Data())
const double * getAngularVelocityCovariance() const
Hardware interface to support reading the state of an IMU sensor.
const double * getAngularVelocity() const
const double * getLinearAcceleration() const
const double * getLinearAccelerationCovariance() const
double * linear_acceleration
A pointer to the storage of the linear acceleration value: a triplet (x,y,z)
std::string frame_id
The reference frame to which this sensor is associated.
A handle used to read the state of a IMU sensor.
double * angular_velocity
A pointer to the storage of the angular velocity value: a triplet (x,y,z)
double * linear_acceleration_covariance
A pointer to the storage of the linear acceleration covariance value: a row major 3x3 matrix about (x...
Base class for handling hardware resources.
std::string name
The name of the sensor.
const double * getOrientationCovariance() const
ImuSensorHandle(const std::string &name, const std::string &frame_id, const double *orientation, const double *orientation_covariance, const double *angular_velocity, const double *angular_velocity_covariance, const double *linear_acceleration, const double *linear_acceleration_covariance)
double * orientation_covariance
A pointer to the storage of the orientation covariance value: a row major 3x3 matrix about (x...


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Mon Apr 20 2020 03:52:05