Go to the documentation of this file.
30 #ifndef PHIDGETS_API_ACCELEROMETER_H
31 #define PHIDGETS_API_ACCELEROMETER_H
35 #include <libphidget22/phidget22.h>
47 int32_t serial_number,
int hub_port,
bool is_hub_port_device,
48 std::function<
void(
const double[3],
double)> data_handler);
53 double ×tamp)
const;
57 void dataHandler(
const double acceleration[3],
double timestamp)
const;
63 static void DataHandler(PhidgetAccelerometerHandle input_handle,
void *ctx,
64 const double acceleration[3],
double timestamp);
69 #endif // PHIDGETS_API_ACCELEROMETER_H
PhidgetAccelerometerHandle accel_handle_
void setDataInterval(uint32_t interval_ms) const
void getAcceleration(double &x, double &y, double &z, double ×tamp) const
void dataHandler(const double acceleration[3], double timestamp) const
static void DataHandler(PhidgetAccelerometerHandle input_handle, void *ctx, const double acceleration[3], double timestamp)
Accelerometer(int32_t serial_number, int hub_port, bool is_hub_port_device, std::function< void(const double[3], double)> data_handler)
std::function< void(const double[3], double)> data_handler_
#define PHIDGET22_NO_COPY_NO_MOVE_NO_ASSIGN(Classname)
phidgets_api
Author(s): Tully Foote, Ivan Dryanovski
autogenerated on Sun May 11 2025 02:20:27