spatial.h
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 #ifndef PHIDGETS_API_SPATIAL_H
31 #define PHIDGETS_API_SPATIAL_H
32 
33 #include <functional>
34 
35 #include <libphidget22/phidget22.h>
36 
37 #include "phidgets_api/phidget22.h"
38 
39 namespace phidgets {
40 
41 class Spatial final
42 {
43  public:
45 
46  explicit Spatial(
47  int32_t serial_number, int hub_port, bool is_hub_port_device,
48  std::function<void(const double[3], const double[3], const double[3],
49  double)>
50  data_handler,
51  std::function<void(const double[4], double)> algorithm_data_handler,
52  std::function<void()> attach_handler = nullptr,
53  std::function<void()> detach_handler = nullptr);
54 
55  ~Spatial();
56 
57  void setCompassCorrectionParameters(double cc_mag_field, double cc_offset0,
58  double cc_offset1, double cc_offset2,
59  double cc_gain0, double cc_gain1,
60  double cc_gain2, double cc_T0,
61  double cc_T1, double cc_T2,
62  double cc_T3, double cc_T4,
63  double cc_T5);
64 
65  void setSpatialAlgorithm(const std::string algorithm);
66 
67  void setAHRSParameters(double angularVelocityThreshold,
68  double angularVelocityDeltaThreshold,
69  double accelerationThreshold, double magTime,
70  double accelTime, double biasTime);
71 
72  void setAlgorithmMagnetometerGain(double magnetometer_gain);
73 
74  void setHeatingEnabled(bool heating_enabled);
75 
76  void setDataInterval(uint32_t interval_ms) const;
77 
78  void zero() const;
79 
80  void dataHandler(const double acceleration[3], const double angular_rate[3],
81  const double magnetic_field[3], double timestamp) const;
82 
83  void algorithmDataHandler(const double quaternion[4],
84  double timestamp) const;
85 
86  virtual void attachHandler();
87  virtual void detachHandler();
88 
89  private:
90  std::function<void(const double[3], const double[3], const double[3],
91  double)>
93 
94  std::function<void(const double quaternion[4], double)>
96 
97  std::function<void()> attach_handler_;
98  std::function<void()> detach_handler_;
99 
100  PhidgetSpatialHandle spatial_handle_{nullptr};
101 
102  static void DataHandler(PhidgetSpatialHandle input_handle, void *ctx,
103  const double acceleration[3],
104  const double angular_rate[3],
105  const double magnetic_field[3], double timestamp);
106  static void AlgorithmDataHandler(PhidgetSpatialHandle input_handle,
107  void *ctx, const double quaternion[4],
108  double timestamp);
109  static void AttachHandler(PhidgetHandle input_handle, void *ctx);
110  static void DetachHandler(PhidgetHandle input_handle, void *ctx);
111 };
112 
113 } // namespace phidgets
114 
115 #endif // PHIDGETS_API_SPATIAL_H
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
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::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::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
PHIDGET22_NO_COPY_NO_MOVE_NO_ASSIGN
#define PHIDGET22_NO_COPY_NO_MOVE_NO_ASSIGN(Classname)
Definition: phidget22.h:38
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