spatial.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, Open Source Robotics Foundation
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <functional>
31 #include <utility>
32 
33 #include <libphidget22/phidget22.h>
34 
35 #include "phidgets_api/phidget22.h"
36 #include "phidgets_api/spatial.h"
37 
38 namespace phidgets {
39 
41  int32_t serial_number, int hub_port, bool is_hub_port_device,
42  std::function<void(const double[3], const double[3], const double[3],
43  double)>
44  data_handler,
45  std::function<void(const double[4], double)> algorithm_data_handler,
46  std::function<void()> attach_handler, std::function<void()> detach_handler)
47  : data_handler_(std::move(data_handler)),
48  algorithm_data_handler_(std::move(algorithm_data_handler)),
49  attach_handler_(std::move(attach_handler)),
50  detach_handler_(std::move(detach_handler))
51 {
52  PhidgetReturnCode ret = PhidgetSpatial_create(&spatial_handle_);
53  if (ret != EPHIDGET_OK)
54  {
55  throw Phidget22Error("Failed to create Spatial handle", ret);
56  }
57 
59  reinterpret_cast<PhidgetHandle>(spatial_handle_), serial_number,
60  hub_port, is_hub_port_device, 0);
61 
62  ret = PhidgetSpatial_setOnSpatialDataHandler(spatial_handle_, DataHandler,
63  this);
64  if (ret != EPHIDGET_OK)
65  {
66  throw Phidget22Error("Failed to set change handler for Spatial", ret);
67  }
68 
69  if (algorithm_data_handler_ != nullptr)
70  {
71  ret = PhidgetSpatial_setOnAlgorithmDataHandler(
73  if (ret != EPHIDGET_OK)
74  {
75  throw Phidget22Error("Failed to set algorithm handler for Spatial",
76  ret);
77  }
78  }
79 
80  if (attach_handler_ != nullptr)
81  {
82  ret = Phidget_setOnAttachHandler(
83  reinterpret_cast<PhidgetHandle>(spatial_handle_), AttachHandler,
84  this);
85  if (ret != EPHIDGET_OK)
86  {
87  throw Phidget22Error("Failed to set attach handler for Spatial",
88  ret);
89  }
90  }
91 
92  if (detach_handler_ != nullptr)
93  {
94  ret = Phidget_setOnDetachHandler(
95  reinterpret_cast<PhidgetHandle>(spatial_handle_), DetachHandler,
96  this);
97  if (ret != EPHIDGET_OK)
98  {
99  throw Phidget22Error("Failed to set detach handler for Spatial",
100  ret);
101  }
102  }
103 }
104 
106 {
107  auto handle = reinterpret_cast<PhidgetHandle>(spatial_handle_);
108  helpers::closeAndDelete(&handle);
109 }
110 
111 void Spatial::zero() const
112 {
113  PhidgetReturnCode ret = PhidgetSpatial_zeroGyro(spatial_handle_);
114  if (ret != EPHIDGET_OK)
115  {
116  throw Phidget22Error("Failed to calibrate Gyroscope", ret);
117  }
118 }
119 
121  double cc_mag_field, double cc_offset0, double cc_offset1,
122  double cc_offset2, double cc_gain0, double cc_gain1, double cc_gain2,
123  double cc_T0, double cc_T1, double cc_T2, double cc_T3, double cc_T4,
124  double cc_T5)
125 {
126  PhidgetReturnCode ret = PhidgetSpatial_setMagnetometerCorrectionParameters(
127  spatial_handle_, cc_mag_field, cc_offset0, cc_offset1, cc_offset2,
128  cc_gain0, cc_gain1, cc_gain2, cc_T0, cc_T1, cc_T2, cc_T3, cc_T4, cc_T5);
129  if (ret != EPHIDGET_OK)
130  {
131  throw Phidget22Error("Failed to set magnetometer correction parameters",
132  ret);
133  }
134 }
135 
136 void Spatial::setSpatialAlgorithm(const std::string algorithm_name)
137 {
138  Phidget_SpatialAlgorithm algorithm;
139 
140  if (algorithm_name.compare("none") == 0)
141  {
142  algorithm = SPATIAL_ALGORITHM_NONE;
143  } else if (algorithm_name.compare("ahrs") == 0)
144  {
145  algorithm = SPATIAL_ALGORITHM_AHRS;
146  } else if (algorithm_name.compare("imu") == 0)
147  {
148  algorithm = SPATIAL_ALGORITHM_IMU;
149  } else
150  {
151  throw std::invalid_argument("Unknown spatial algorithm name");
152  }
153 
154  PhidgetReturnCode ret =
155  PhidgetSpatial_setAlgorithm(spatial_handle_, algorithm);
156  if (ret != EPHIDGET_OK)
157  {
158  throw Phidget22Error("Failed to set spatial algorithm", ret);
159  }
160 }
161 
162 void Spatial::setAHRSParameters(double angularVelocityThreshold,
163  double angularVelocityDeltaThreshold,
164  double accelerationThreshold, double magTime,
165  double accelTime, double biasTime)
166 {
167  PhidgetReturnCode ret = PhidgetSpatial_setAHRSParameters(
168  spatial_handle_, angularVelocityThreshold,
169  angularVelocityDeltaThreshold, accelerationThreshold, magTime,
170  accelTime, biasTime);
171  if (ret != EPHIDGET_OK)
172  {
173  throw Phidget22Error("Failed to set AHRS parameters", ret);
174  }
175 }
176 
177 void Spatial::setAlgorithmMagnetometerGain(double magnetometer_gain)
178 {
179  PhidgetReturnCode ret = PhidgetSpatial_setAlgorithmMagnetometerGain(
180  spatial_handle_, magnetometer_gain);
181  if (ret != EPHIDGET_OK)
182  {
183  throw Phidget22Error("Failed to set algorithm magnetometer gain", ret);
184  }
185 }
186 
187 void Spatial::setHeatingEnabled(bool heating_enabled)
188 {
189  PhidgetReturnCode ret =
190  PhidgetSpatial_setHeatingEnabled(spatial_handle_, heating_enabled);
191  if (ret != EPHIDGET_OK)
192  {
193  throw Phidget22Error("Failed to set heating flag", ret);
194  }
195 }
196 
197 void Spatial::setDataInterval(uint32_t interval_ms) const
198 {
199  PhidgetReturnCode ret =
200  PhidgetSpatial_setDataInterval(spatial_handle_, interval_ms);
201  if (ret != EPHIDGET_OK)
202  {
203  throw Phidget22Error("Failed to set data interval", ret);
204  }
205 }
206 
207 void Spatial::dataHandler(const double acceleration[3],
208  const double angular_rate[3],
209  const double magnetic_field[3],
210  double timestamp) const
211 {
212  data_handler_(acceleration, angular_rate, magnetic_field, timestamp);
213 }
214 
215 void Spatial::algorithmDataHandler(const double quaternion[4],
216  double timestamp) const
217 {
218  algorithm_data_handler_(quaternion, timestamp);
219 }
220 
222 {
223  attach_handler_();
224 }
225 
227 {
228  detach_handler_();
229 }
230 
231 void Spatial::DataHandler(PhidgetSpatialHandle /* input_handle */, void *ctx,
232  const double acceleration[3],
233  const double angular_rate[3],
234  const double magnetic_field[3], double timestamp)
235 {
236  ((Spatial *)ctx)
237  ->dataHandler(acceleration, angular_rate, magnetic_field, timestamp);
238 }
239 
240 void Spatial::AlgorithmDataHandler(PhidgetSpatialHandle /* input_handle */,
241  void *ctx, const double quaternion[4],
242  double timestamp)
243 {
244  ((Spatial *)ctx)->algorithmDataHandler(quaternion, timestamp);
245 }
246 
247 void Spatial::AttachHandler(PhidgetHandle /* input_handle */, void *ctx)
248 {
249  ((Spatial *)ctx)->attachHandler();
250 }
251 
252 void Spatial::DetachHandler(PhidgetHandle /* input_handle */, void *ctx)
253 {
254  ((Spatial *)ctx)->detachHandler();
255 }
256 
257 } // namespace phidgets
phidgets
Definition: accelerometer.h:39
phidgets::Spatial::data_handler_
std::function< void(const double[3], const double[3], const double[3], double)> data_handler_
Definition: spatial.h:92
phidgets::Spatial::setHeatingEnabled
void setHeatingEnabled(bool heating_enabled)
Definition: spatial.cpp:187
phidgets::Spatial::setCompassCorrectionParameters
void setCompassCorrectionParameters(double cc_mag_field, double cc_offset0, double cc_offset1, double cc_offset2, double cc_gain0, double cc_gain1, double cc_gain2, double cc_T0, double cc_T1, double cc_T2, double cc_T3, double cc_T4, double cc_T5)
Definition: spatial.cpp:120
phidgets::Spatial::attach_handler_
std::function< void()> attach_handler_
Definition: spatial.h:97
spatial.h
phidgets::Spatial::AlgorithmDataHandler
static void AlgorithmDataHandler(PhidgetSpatialHandle input_handle, void *ctx, const double quaternion[4], double timestamp)
Definition: spatial.cpp:240
phidgets::Spatial::zero
void zero() const
Definition: spatial.cpp:111
phidgets::Spatial::setDataInterval
void setDataInterval(uint32_t interval_ms) const
Definition: spatial.cpp:197
phidgets::Spatial::~Spatial
~Spatial()
Definition: spatial.cpp:105
phidgets::Spatial::attachHandler
virtual void attachHandler()
Definition: spatial.cpp:221
phidgets::Spatial::algorithm_data_handler_
std::function< void(const double quaternion[4], double)> algorithm_data_handler_
Definition: spatial.h:95
phidgets::Spatial::spatial_handle_
PhidgetSpatialHandle spatial_handle_
Definition: spatial.h:100
phidgets::helpers::openWaitForAttachment
void openWaitForAttachment(PhidgetHandle handle, int32_t serial_number, int hub_port, bool is_hub_port_device, int channel)
Definition: phidget22.cpp:57
phidgets::helpers::closeAndDelete
void closeAndDelete(PhidgetHandle *handle) noexcept
Definition: phidget22.cpp:93
phidgets::Spatial::dataHandler
void dataHandler(const double acceleration[3], const double angular_rate[3], const double magnetic_field[3], double timestamp) const
Definition: spatial.cpp:207
phidget22.h
phidgets::Phidget22Error
Definition: phidget22.h:46
phidgets::Spatial::detachHandler
virtual void detachHandler()
Definition: spatial.cpp:226
phidgets::Spatial::DetachHandler
static void DetachHandler(PhidgetHandle input_handle, void *ctx)
Definition: spatial.cpp:252
phidgets::Spatial::detach_handler_
std::function< void()> detach_handler_
Definition: spatial.h:98
phidgets::Spatial::setAlgorithmMagnetometerGain
void setAlgorithmMagnetometerGain(double magnetometer_gain)
Definition: spatial.cpp:177
phidgets::Spatial
Definition: spatial.h:41
phidgets::Spatial::algorithmDataHandler
void algorithmDataHandler(const double quaternion[4], double timestamp) const
Definition: spatial.cpp:215
phidgets::Spatial::Spatial
Spatial(int32_t serial_number, int hub_port, bool is_hub_port_device, std::function< void(const double[3], const double[3], const double[3], double)> data_handler, std::function< void(const double[4], double)> algorithm_data_handler, std::function< void()> attach_handler=nullptr, std::function< void()> detach_handler=nullptr)
Definition: spatial.cpp:40
phidgets::Spatial::setSpatialAlgorithm
void setSpatialAlgorithm(const std::string algorithm)
Definition: spatial.cpp:136
phidgets::Spatial::DataHandler
static void DataHandler(PhidgetSpatialHandle input_handle, void *ctx, const double acceleration[3], const double angular_rate[3], const double magnetic_field[3], double timestamp)
Definition: spatial.cpp:231
phidgets::Spatial::setAHRSParameters
void setAHRSParameters(double angularVelocityThreshold, double angularVelocityDeltaThreshold, double accelerationThreshold, double magTime, double accelTime, double biasTime)
Definition: spatial.cpp:162
phidgets::Spatial::AttachHandler
static void AttachHandler(PhidgetHandle input_handle, void *ctx)
Definition: spatial.cpp:247


phidgets_api
Author(s): Tully Foote, Ivan Dryanovski
autogenerated on Sun May 11 2025 02:20:27