magnetometer.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 <memory>
32 #include <stdexcept>
33 #include <string>
34 
35 #include <libphidget22/phidget22.h>
36 
38 #include "phidgets_api/phidget22.h"
39 
40 namespace phidgets {
41 
43  int32_t serial_number, int hub_port, bool is_hub_port_device,
44  std::function<void(const double[3], double)> data_handler)
45  : data_handler_(data_handler)
46 {
47  PhidgetReturnCode ret = PhidgetMagnetometer_create(&mag_handle_);
48  if (ret != EPHIDGET_OK)
49  {
50  throw Phidget22Error("Failed to create Magnetometer handle", ret);
51  }
52 
53  helpers::openWaitForAttachment(reinterpret_cast<PhidgetHandle>(mag_handle_),
54  serial_number, hub_port, is_hub_port_device,
55  0);
56 
57  ret = PhidgetMagnetometer_setOnMagneticFieldChangeHandler(
58  mag_handle_, DataHandler, this);
59  if (ret != EPHIDGET_OK)
60  {
61  throw Phidget22Error("Failed to set change handler for Magnetometer",
62  ret);
63  }
64 }
65 
67 {
68  PhidgetHandle handle = reinterpret_cast<PhidgetHandle>(mag_handle_);
69  helpers::closeAndDelete(&handle);
70 }
71 
73  double cc_mag_field, double cc_offset0, double cc_offset1,
74  double cc_offset2, double cc_gain0, double cc_gain1, double cc_gain2,
75  double cc_T0, double cc_T1, double cc_T2, double cc_T3, double cc_T4,
76  double cc_T5)
77 {
78  PhidgetReturnCode ret = PhidgetMagnetometer_setCorrectionParameters(
79  mag_handle_, cc_mag_field, cc_offset0, cc_offset1, cc_offset2, cc_gain0,
80  cc_gain1, cc_gain2, cc_T0, cc_T1, cc_T2, cc_T3, cc_T4, cc_T5);
81  if (ret != EPHIDGET_OK)
82  {
83  throw Phidget22Error("Failed to set magnetometer correction parameters",
84  ret);
85  }
86 }
87 
88 void Magnetometer::getMagneticField(double &x, double &y, double &z,
89  double &timestamp) const
90 {
91  double mag_field[3];
92  PhidgetReturnCode ret =
93  PhidgetMagnetometer_getMagneticField(mag_handle_, &mag_field);
94  if (ret != EPHIDGET_OK)
95  {
96  throw Phidget22Error("Failed to get magnetic field", ret);
97  }
98 
99  x = mag_field[0];
100  y = mag_field[1];
101  z = mag_field[2];
102 
103  double ts;
104  ret = PhidgetMagnetometer_getTimestamp(mag_handle_, &ts);
105  if (ret != EPHIDGET_OK)
106  {
107  throw Phidget22Error("Failed to get magnetic field timestamp", ret);
108  }
109 
110  timestamp = ts;
111 }
112 
113 void Magnetometer::setDataInterval(uint32_t interval_ms) const
114 {
115  PhidgetReturnCode ret =
116  PhidgetMagnetometer_setDataInterval(mag_handle_, interval_ms);
117  if (ret != EPHIDGET_OK)
118  {
119  throw Phidget22Error("Failed to set data interval", ret);
120  }
121 }
122 
123 void Magnetometer::dataHandler(const double magnetic_field[3],
124  double timestamp) const
125 {
126  data_handler_(magnetic_field, timestamp);
127 }
128 
129 void Magnetometer::DataHandler(PhidgetMagnetometerHandle /* input_handle */,
130  void *ctx, const double magnetic_field[3],
131  double timestamp)
132 {
133  ((Magnetometer *)ctx)->dataHandler(magnetic_field, timestamp);
134 }
135 
136 } // namespace phidgets
phidgets
Definition: accelerometer.h:39
phidgets::Magnetometer::mag_handle_
PhidgetMagnetometerHandle mag_handle_
Definition: magnetometer.h:69
phidgets::Magnetometer::DataHandler
static void DataHandler(PhidgetMagnetometerHandle input_handle, void *ctx, const double magnetic_field[3], double timestamp)
Definition: magnetometer.cpp:129
magnetometer.h
phidgets::Magnetometer::setDataInterval
void setDataInterval(uint32_t interval_ms) const
Definition: magnetometer.cpp:113
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::Magnetometer
Definition: magnetometer.h:41
phidgets::helpers::closeAndDelete
void closeAndDelete(PhidgetHandle *handle) noexcept
Definition: phidget22.cpp:93
phidgets::Magnetometer::data_handler_
std::function< void(const double[3], double)> data_handler_
Definition: magnetometer.h:68
phidgets::Magnetometer::getMagneticField
void getMagneticField(double &x, double &y, double &z, double &timestamp) const
Definition: magnetometer.cpp:88
phidget22.h
phidgets::Phidget22Error
Definition: phidget22.h:46
phidgets::Magnetometer::dataHandler
void dataHandler(const double magnetic_field[3], double timestamp) const
Definition: magnetometer.cpp:123
phidgets::Magnetometer::~Magnetometer
~Magnetometer()
Definition: magnetometer.cpp:66
phidgets::Magnetometer::Magnetometer
Magnetometer(int32_t serial_number, int hub_port, bool is_hub_port_device, std::function< void(const double[3], double)> data_handler)
Definition: magnetometer.cpp:42
phidgets::Magnetometer::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: magnetometer.cpp:72


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