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 #pragma once
31 
32 
34 #include <string>
35 
36 namespace hardware_interface
37 {
38 
45 {
46 public:
47  struct Data
48  {
49  // Note: User-provided constructor required due to a defect in the standard. See https://stackoverflow.com/a/17436088/1932358
50  Data() {}
51 
52  std::string name;
53  std::string frame_id;
54  double* orientation = {nullptr};
55  double* orientation_covariance = {nullptr};
56  double* angular_velocity = {nullptr};
57  double* angular_velocity_covariance = {nullptr};
58  double* linear_acceleration = {nullptr};
59  double* linear_acceleration_covariance = {nullptr};
60  };
61 
62  ImuSensorHandle(const Data& data = {})
63  : name_(data.name),
64  frame_id_(data.frame_id),
65  orientation_(data.orientation),
66  orientation_covariance_(data.orientation_covariance),
67  angular_velocity_(data.angular_velocity),
68  angular_velocity_covariance_(data.angular_velocity_covariance),
69  linear_acceleration_(data.linear_acceleration),
70  linear_acceleration_covariance_(data.linear_acceleration_covariance)
71  {}
72 
74  const std::string& name,
75  const std::string& frame_id,
76  const double* orientation,
77  const double* orientation_covariance,
78  const double* angular_velocity,
79  const double* angular_velocity_covariance,
80  const double* linear_acceleration,
81  const double* linear_acceleration_covariance
82  )
83  : name_(name),
84  frame_id_(frame_id),
85  orientation_(orientation),
86  orientation_covariance_(orientation_covariance),
87  angular_velocity_(angular_velocity),
88  angular_velocity_covariance_(angular_velocity_covariance),
89  linear_acceleration_(linear_acceleration),
90  linear_acceleration_covariance_(linear_acceleration_covariance)
91  {}
92 
93  std::string getName() const {return name_;}
94  std::string getFrameId() const {return frame_id_;}
95  const double* getOrientation() const {return orientation_;}
96  const double* getOrientationCovariance() const {return orientation_covariance_;}
97  const double* getAngularVelocity() const {return angular_velocity_;}
99  const double* getLinearAcceleration() const {return linear_acceleration_;}
101 
102 private:
103  std::string name_;
104  std::string frame_id_;
105 
106  const double* orientation_;
107  const double* orientation_covariance_;
108  const double* angular_velocity_;
110  const double* linear_acceleration_;
112 };
113 
115 class ImuSensorInterface : public HardwareResourceManager<ImuSensorHandle> {};
116 
117 }
hardware_interface::ImuSensorHandle::name_
std::string name_
Definition: imu_sensor_interface.h:103
hardware_interface::ImuSensorHandle::Data::orientation
double * orientation
A pointer to the storage of the orientation value: a quaternion (x,y,z,w)
Definition: imu_sensor_interface.h:54
hardware_interface::ImuSensorHandle::orientation_covariance_
const double * orientation_covariance_
Definition: imu_sensor_interface.h:107
hardware_interface::ImuSensorHandle
A handle used to read the state of a IMU sensor.
Definition: imu_sensor_interface.h:44
hardware_interface::ImuSensorHandle::getFrameId
std::string getFrameId() const
Definition: imu_sensor_interface.h:94
hardware_interface::ImuSensorHandle::getAngularVelocity
const double * getAngularVelocity() const
Definition: imu_sensor_interface.h:97
hardware_interface::ImuSensorHandle::getOrientation
const double * getOrientation() const
Definition: imu_sensor_interface.h:95
hardware_interface::ImuSensorHandle::getAngularVelocityCovariance
const double * getAngularVelocityCovariance() const
Definition: imu_sensor_interface.h:98
hardware_interface::ImuSensorHandle::linear_acceleration_
const double * linear_acceleration_
Definition: imu_sensor_interface.h:110
hardware_interface::ImuSensorHandle::getOrientationCovariance
const double * getOrientationCovariance() const
Definition: imu_sensor_interface.h:96
hardware_interface::ImuSensorHandle::Data::linear_acceleration
double * linear_acceleration
A pointer to the storage of the linear acceleration value: a triplet (x,y,z)
Definition: imu_sensor_interface.h:58
hardware_interface
Definition: actuator_command_interface.h:36
hardware_interface::ImuSensorHandle::Data::frame_id
std::string frame_id
The reference frame to which this sensor is associated.
Definition: imu_sensor_interface.h:53
hardware_interface::ImuSensorHandle::getLinearAcceleration
const double * getLinearAcceleration() const
Definition: imu_sensor_interface.h:99
hardware_interface::ImuSensorInterface
Hardware interface to support reading the state of an IMU sensor.
Definition: imu_sensor_interface.h:115
hardware_interface::ImuSensorHandle::frame_id_
std::string frame_id_
Definition: imu_sensor_interface.h:104
hardware_interface::ImuSensorHandle::ImuSensorHandle
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)
Definition: imu_sensor_interface.h:73
hardware_interface::ImuSensorHandle::angular_velocity_
const double * angular_velocity_
Definition: imu_sensor_interface.h:108
hardware_interface::ImuSensorHandle::linear_acceleration_covariance_
const double * linear_acceleration_covariance_
Definition: imu_sensor_interface.h:111
hardware_interface::ImuSensorHandle::Data
Definition: imu_sensor_interface.h:47
hardware_interface::ImuSensorHandle::orientation_
const double * orientation_
Definition: imu_sensor_interface.h:106
hardware_interface::ImuSensorHandle::Data::name
std::string name
The name of the sensor.
Definition: imu_sensor_interface.h:52
hardware_interface::ImuSensorHandle::Data::angular_velocity
double * angular_velocity
A pointer to the storage of the angular velocity value: a triplet (x,y,z)
Definition: imu_sensor_interface.h:56
hardware_interface::ImuSensorHandle::getName
std::string getName() const
Definition: imu_sensor_interface.h:93
hardware_interface::ImuSensorHandle::Data::linear_acceleration_covariance
double * linear_acceleration_covariance
A pointer to the storage of the linear acceleration covariance value: a row major 3x3 matrix about (x...
Definition: imu_sensor_interface.h:59
hardware_interface::ImuSensorHandle::Data::orientation_covariance
double * orientation_covariance
A pointer to the storage of the orientation covariance value: a row major 3x3 matrix about (x,...
Definition: imu_sensor_interface.h:55
hardware_interface::ImuSensorHandle::Data::Data
Data()
Definition: imu_sensor_interface.h:50
hardware_interface::ImuSensorHandle::ImuSensorHandle
ImuSensorHandle(const Data &data={})
Definition: imu_sensor_interface.h:62
hardware_interface::ImuSensorHandle::getLinearAccelerationCovariance
const double * getLinearAccelerationCovariance() const
Definition: imu_sensor_interface.h:100
hardware_interface::ImuSensorHandle::angular_velocity_covariance_
const double * angular_velocity_covariance_
Definition: imu_sensor_interface.h:109
hardware_interface::HardwareResourceManager
Base class for handling hardware resources.
Definition: hardware_resource_manager.h:79
hardware_interface::ImuSensorHandle::Data::angular_velocity_covariance
double * angular_velocity_covariance
A pointer to the storage of the angular velocity covariance value: a row major 3x3 matrix about (x,...
Definition: imu_sensor_interface.h:57
hardware_resource_manager.h


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Nov 3 2023 02:07:57