XsensIMU.cpp
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5 *
6 * ArmarX is free software; you can redistribute it and/or modify
7 * it under the terms of the GNU General Public License version 2 as
8 * published by the Free Software Foundation.
9 *
10 * ArmarX is distributed in the hope that it will be useful, but
11 * WITHOUT ANY WARRANTY; without even the implied warranty of
12 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 * GNU General Public License for more details.
14 *
15 * You should have received a copy of the GNU General Public License
16 * along with this program. If not, see <http://www.gnu.org/licenses/>.
17 *
18 * @package RobotAPI::ArmarXObjects::XsensIMU
19 * @author Markus Grotz ( markus-grotz at web dot de )
20 * @date 2015
21 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22 * GNU General Public License
23 */
24
25#include "XsensIMU.h"
26
27namespace armarx
28{
29 using namespace IMU;
30
36
37 void
39 {
40
41 std::vector<float> offset(3, 0.0);
42
43 int count = 0;
44
45 IceUtil::Time startTime = armarx::TimeUtil::GetTime();
46
47 if (getProperty<bool>("EnableSimpleCalibration").getValue())
48 {
49 ARMARX_WARNING << "Estimation of the offset for the IMU, please do not move the IMU";
50 while (((armarx::TimeUtil::GetTime() - startTime) < IceUtil::Time::seconds(5)) &&
51 !sensorTask->isStopped())
52 {
53
54 while (HasPendingEvents())
55 {
57
58 offset[0] += m_GyroscopeRotation[0];
59 offset[1] += m_GyroscopeRotation[1];
60 offset[2] += m_GyroscopeRotation[2];
61
62 count++;
63 }
64 }
65
66 offset[0] /= count;
67 offset[1] /= count;
68 offset[2] /= count;
69 }
70
71
72 while (!sensorTask->isStopped())
73 {
74
75 while (HasPendingEvents())
76 {
77
79
81 IMUData data;
82
83 data.acceleration.push_back(m_Accelaration[0]);
84 data.acceleration.push_back(m_Accelaration[1]);
85 data.acceleration.push_back(m_Accelaration[2]);
86
87 data.gyroscopeRotation.push_back(m_GyroscopeRotation[0] - offset[0]);
88 data.gyroscopeRotation.push_back(m_GyroscopeRotation[1] - offset[1]);
89 data.gyroscopeRotation.push_back(m_GyroscopeRotation[2] - offset[2]);
90
91
92 data.magneticRotation.push_back(m_MagneticRotation[0]);
93 data.magneticRotation.push_back(m_MagneticRotation[1]);
94 data.magneticRotation.push_back(m_MagneticRotation[2]);
95
96
97 data.orientationQuaternion.push_back(m_OrientationQuaternion[0]);
98 data.orientationQuaternion.push_back(m_OrientationQuaternion[1]);
99 data.orientationQuaternion.push_back(m_OrientationQuaternion[2]);
100 data.orientationQuaternion.push_back(m_OrientationQuaternion[3]);
101
102 IMUTopicPrx->reportSensorValues("XsensIMU", "XsensIMU", data, now);
103 }
104
105 usleep(10000);
106 }
107 }
108
109 /*
110 void XsensIMU::OnIMUCycle(const timeval& TimeStamp, const CIMUDevice* pIMUDevice)
111 {
112 const IMUState CurrentState = pIMUDevice->GetIMUState();
113
114 TimestampVariantPtr now = TimestampVariant::nowPtr();
115 IMUData data;
116
117 data.acceleration.push_back(CurrentState.m_PhysicalData.m_Acceleration[0]);
118 data.acceleration.push_back(CurrentState.m_PhysicalData.m_Acceleration[1]);
119 data.acceleration.push_back(CurrentState.m_PhysicalData.m_Acceleration[2]);
120
121 data.gyroscopeRotation.push_back(CurrentState.m_PhysicalData.m_GyroscopeRotation[0]);
122 data.gyroscopeRotation.push_back(CurrentState.m_PhysicalData.m_GyroscopeRotation[1]);
123 data.gyroscopeRotation.push_back(CurrentState.m_PhysicalData.m_GyroscopeRotation[2]);
124
125 data.magneticRotation.push_back(CurrentState.m_PhysicalData.m_MagneticRotation[0]);
126 data.magneticRotation.push_back(CurrentState.m_PhysicalData.m_MagneticRotation[1]);
127 data.magneticRotation.push_back(CurrentState.m_PhysicalData.m_MagneticRotation[2]);
128
129 data.orientationQuaternion.push_back(CurrentState.m_PhysicalData.m_OrientationQuaternion[0]);
130 data.orientationQuaternion.push_back(CurrentState.m_PhysicalData.m_OrientationQuaternion[1]);
131 data.orientationQuaternion.push_back(CurrentState.m_PhysicalData.m_OrientationQuaternion[2]);
132 data.orientationQuaternion.push_back(CurrentState.m_PhysicalData.m_OrientationQuaternion[3]);
133
134 IMUTopicPrx->reportSensorValues("XsensIMU", pIMUDevice->GetDeviceId(), data, now);
135
136 }
137
138 */
139
140 void
142 {
144
147
148 //IMUDevice.SetFusion(IMU::CIMUDevice::eGaussianFusion, 2);
149 IMUDevice.RegisterEventDispatcher(this);
150
151 IMUDevice.Connect(_IMU_DEVICE_DEFAUL_CONNECTION_,
153 }
154
155 void
157 {
158 IMUDevice.Start(false);
159 sensorTask->start();
160 }
161
162 void
164 {
165 IMUDevice.Stop();
166 sensorTask->stop();
167 }
168} // namespace armarx
#define _IMU_DEVICE_DEFAUL_CONNECTION_
Definition IMUDevice.h:23
@ eSamplingFrequency_120HZ
Definition IMUDevice.h:83
void SetMaximalPendingEvents(const uint32_t MaximalPendingEvents)
void SetDispatchingMode(const DispatchingMode Mode)
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition Component.cpp:90
Property< PropertyType > getProperty(const std::string &name)
InertialMeasurementUnitListenerPrx IMUTopicPrx
static IceUtil::Time GetTime(TimeMode timeMode=TimeMode::VirtualTime)
Get the current time.
Definition TimeUtil.cpp:42
static TimestampVariantPtr nowPtr()
void frameAcquisitionTaskLoop()
Definition XsensIMU.cpp:38
void onExitIMU() override
Definition XsensIMU.cpp:163
void onStartIMU() override
Definition XsensIMU.cpp:156
void onInitIMU() override
Definition XsensIMU.cpp:141
PropertyDefinitionsPtr createPropertyDefinitions() override
Definition XsensIMU.cpp:32
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:193
This file offers overloads of toIce() and fromIce() functions for STL container types.
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
IceInternal::Handle< TimestampVariant > TimestampVariantPtr