accelerometer.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 = PhidgetAccelerometer_create(&accel_handle_);
48  if (ret != EPHIDGET_OK)
49  {
50  throw Phidget22Error("Failed to create Accelerometer handle", ret);
51  }
52 
54  reinterpret_cast<PhidgetHandle>(accel_handle_), serial_number, hub_port,
55  is_hub_port_device, 0);
56 
57  ret = PhidgetAccelerometer_setOnAccelerationChangeHandler(
58  accel_handle_, DataHandler, this);
59  if (ret != EPHIDGET_OK)
60  {
61  throw Phidget22Error("Failed to set change handler for acceleration",
62  ret);
63  }
64 }
65 
67 {
68  PhidgetHandle handle = reinterpret_cast<PhidgetHandle>(accel_handle_);
69  helpers::closeAndDelete(&handle);
70 }
71 
72 void Accelerometer::getAcceleration(double &x, double &y, double &z,
73  double &timestamp) const
74 {
75  double accel[3];
76  PhidgetReturnCode ret =
77  PhidgetAccelerometer_getAcceleration(accel_handle_, &accel);
78  if (ret != EPHIDGET_OK)
79  {
80  throw Phidget22Error("Failed to get acceleration", ret);
81  }
82 
83  x = accel[0];
84  y = accel[1];
85  z = accel[2];
86 
87  double ts;
88  ret = PhidgetAccelerometer_getTimestamp(accel_handle_, &ts);
89  if (ret != EPHIDGET_OK)
90  {
91  throw Phidget22Error("Failed to get acceleration timestamp", ret);
92  }
93 
94  timestamp = ts;
95 }
96 
97 void Accelerometer::setDataInterval(uint32_t interval_ms) const
98 {
99  PhidgetReturnCode ret =
100  PhidgetAccelerometer_setDataInterval(accel_handle_, interval_ms);
101  if (ret != EPHIDGET_OK)
102  {
103  throw Phidget22Error("Failed to set data interval", ret);
104  }
105 }
106 
107 void Accelerometer::dataHandler(const double acceleration[3],
108  double timestamp) const
109 {
110  data_handler_(acceleration, timestamp);
111 }
112 
113 void Accelerometer::DataHandler(PhidgetAccelerometerHandle /* input_handle */,
114  void *ctx, const double acceleration[3],
115  double timestamp)
116 {
117  ((Accelerometer *)ctx)->dataHandler(acceleration, timestamp);
118 }
119 
120 } // namespace phidgets
phidgets
Definition: accelerometer.h:39
phidgets::Accelerometer::~Accelerometer
~Accelerometer()
Definition: accelerometer.cpp:66
phidgets::Accelerometer::accel_handle_
PhidgetAccelerometerHandle accel_handle_
Definition: accelerometer.h:61
phidgets::Accelerometer::setDataInterval
void setDataInterval(uint32_t interval_ms) const
Definition: accelerometer.cpp:97
phidgets::Accelerometer::getAcceleration
void getAcceleration(double &x, double &y, double &z, double &timestamp) const
Definition: accelerometer.cpp:72
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
accelerometer.h
phidgets::Accelerometer::dataHandler
void dataHandler(const double acceleration[3], double timestamp) const
Definition: accelerometer.cpp:107
phidgets::Accelerometer
Definition: accelerometer.h:41
phidget22.h
phidgets::Phidget22Error
Definition: phidget22.h:46
phidgets::Accelerometer::DataHandler
static void DataHandler(PhidgetAccelerometerHandle input_handle, void *ctx, const double acceleration[3], double timestamp)
Definition: accelerometer.cpp:113
phidgets::Accelerometer::Accelerometer
Accelerometer(int32_t serial_number, int hub_port, bool is_hub_port_device, std::function< void(const double[3], double)> data_handler)
Definition: accelerometer.cpp:42
phidgets::Accelerometer::data_handler_
std::function< void(const double[3], double)> data_handler_
Definition: accelerometer.h:60


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