motor.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 <string>
32 
33 #include <libphidget22/phidget22.h>
34 
35 #include "phidgets_api/motor.h"
36 #include "phidgets_api/phidget22.h"
37 
38 namespace phidgets {
39 
40 Motor::Motor(int32_t serial_number, int hub_port, bool is_hub_port_device,
41  int channel,
42  std::function<void(int, double)> duty_cycle_change_handler,
43  std::function<void(int, double)> back_emf_change_handler)
44  : channel_(channel),
45  duty_cycle_change_handler_(duty_cycle_change_handler),
46  back_emf_change_handler_(back_emf_change_handler)
47 {
48  PhidgetReturnCode ret = PhidgetDCMotor_create(&motor_handle_);
49  if (ret != EPHIDGET_OK)
50  {
51  throw Phidget22Error("Failed to create Motor handle for channel " +
52  std::to_string(channel),
53  ret);
54  }
55 
57  reinterpret_cast<PhidgetHandle>(motor_handle_), serial_number, hub_port,
58  is_hub_port_device, channel);
59 
60  ret = PhidgetDCMotor_setOnVelocityUpdateHandler(
62  if (ret != EPHIDGET_OK)
63  {
64  throw Phidget22Error(
65  "Failed to set duty cycle update handler for Motor channel " +
66  std::to_string(channel),
67  ret);
68  }
69 
70  ret = PhidgetDCMotor_setOnBackEMFChangeHandler(motor_handle_,
71  BackEMFChangeHandler, this);
72  if (ret != EPHIDGET_OK)
73  {
74  throw Phidget22Error(
75  "Failed to set back EMF update handler for Motor channel " +
76  std::to_string(channel),
77  ret);
78  }
79 }
80 
82 {
83  PhidgetHandle handle = reinterpret_cast<PhidgetHandle>(motor_handle_);
84  helpers::closeAndDelete(&handle);
85 }
86 
87 double Motor::getDutyCycle() const
88 {
89  double duty_cycle;
90  PhidgetReturnCode ret =
91  PhidgetDCMotor_getVelocity(motor_handle_, &duty_cycle);
92  if (ret != EPHIDGET_OK)
93  {
94  throw Phidget22Error("Failed to get duty cycle for Motor channel " +
95  std::to_string(channel_),
96  ret);
97  }
98  return duty_cycle;
99 }
100 
101 void Motor::setDutyCycle(double duty_cycle) const
102 {
103  PhidgetReturnCode ret =
104  PhidgetDCMotor_setTargetVelocity(motor_handle_, duty_cycle);
105  if (ret != EPHIDGET_OK)
106  {
107  throw Phidget22Error("Failed to set duty cycle for Motor channel " +
108  std::to_string(channel_),
109  ret);
110  }
111 }
112 
114 {
115  double accel;
116  PhidgetReturnCode ret =
117  PhidgetDCMotor_getAcceleration(motor_handle_, &accel);
118  if (ret != EPHIDGET_OK)
119  {
120  throw Phidget22Error("Failed to get acceleration for Motor channel " +
121  std::to_string(channel_),
122  ret);
123  }
124  return accel;
125 }
126 
127 void Motor::setAcceleration(double acceleration) const
128 {
129  PhidgetReturnCode ret =
130  PhidgetDCMotor_setAcceleration(motor_handle_, acceleration);
131  if (ret != EPHIDGET_OK)
132  {
133  throw Phidget22Error("Failed to set acceleration for Motor channel " +
134  std::to_string(channel_),
135  ret);
136  }
137 }
138 
139 double Motor::getBackEMF() const
140 {
141  double backemf;
142  PhidgetReturnCode ret = PhidgetDCMotor_getBackEMF(motor_handle_, &backemf);
143  if (ret != EPHIDGET_OK)
144  {
145  throw Phidget22Error("Failed to get back EMF for Motor channel " +
146  std::to_string(channel_),
147  ret);
148  }
149  return backemf;
150 }
151 
152 void Motor::setDataInterval(uint32_t data_interval_ms) const
153 {
154  PhidgetReturnCode ret =
155  PhidgetDCMotor_setDataInterval(motor_handle_, data_interval_ms);
156  if (ret != EPHIDGET_OK)
157  {
158  throw Phidget22Error("Failed to set data interval for Motor channel " +
159  std::to_string(channel_),
160  ret);
161  }
162 }
163 
164 double Motor::getBraking() const
165 {
166  double braking;
167  PhidgetReturnCode ret =
168  PhidgetDCMotor_getBrakingStrength(motor_handle_, &braking);
169  if (ret != EPHIDGET_OK)
170  {
171  throw Phidget22Error(
172  "Failed to get braking strength for Motor channel " +
173  std::to_string(channel_),
174  ret);
175  }
176  return braking;
177 }
178 
179 void Motor::setBraking(double braking) const
180 {
181  PhidgetReturnCode ret =
182  PhidgetDCMotor_setTargetBrakingStrength(motor_handle_, braking);
183  if (ret != EPHIDGET_OK)
184  {
185  throw Phidget22Error(
186  "Failed to set braking strength for Motor channel " +
187  std::to_string(channel_),
188  ret);
189  }
190 }
191 
192 void Motor::dutyCycleChangeHandler(double duty_cycle) const
193 {
195 }
196 
197 void Motor::backEMFChangeHandler(double back_emf) const
198 {
200 }
201 
202 void Motor::DutyCycleChangeHandler(PhidgetDCMotorHandle /* motor_handle */,
203  void *ctx, double duty_cycle)
204 {
205  ((Motor *)ctx)->dutyCycleChangeHandler(duty_cycle);
206 }
207 
208 void Motor::BackEMFChangeHandler(PhidgetDCMotorHandle /* motor_handle */,
209  void *ctx, double back_emf)
210 {
211  ((Motor *)ctx)->backEMFChangeHandler(back_emf);
212 }
213 
214 } // namespace phidgets
phidgets
Definition: accelerometer.h:39
phidgets::Motor::DutyCycleChangeHandler
static void DutyCycleChangeHandler(PhidgetDCMotorHandle motor_handle, void *ctx, double duty_cycle)
Definition: motor.cpp:202
phidgets::Motor::back_emf_change_handler_
std::function< void(int, double)> back_emf_change_handler_
Definition: motor.h:70
phidgets::Motor::duty_cycle_change_handler_
std::function< void(int, double)> duty_cycle_change_handler_
Definition: motor.h:69
phidgets::Motor::getDutyCycle
double getDutyCycle() const
Definition: motor.cpp:87
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
motor.h
phidgets::Motor::~Motor
~Motor()
Definition: motor.cpp:81
phidget22.h
phidgets::Phidget22Error
Definition: phidget22.h:46
phidgets::Motor::Motor
Motor(int32_t serial_number, int hub_port, bool is_hub_port_device, int channel, std::function< void(int, double)> duty_cycle_change_handler, std::function< void(int, double)> back_emf_change_handler)
Definition: motor.cpp:40
phidgets::Motor::getAcceleration
double getAcceleration() const
Definition: motor.cpp:113
phidgets::Motor::setDutyCycle
void setDutyCycle(double duty_cycle) const
Definition: motor.cpp:101
phidgets::Motor::getBackEMF
double getBackEMF() const
Definition: motor.cpp:139
phidgets::Motor::BackEMFChangeHandler
static void BackEMFChangeHandler(PhidgetDCMotorHandle motor_handle, void *ctx, double back_emf)
Definition: motor.cpp:208
phidgets::Motor::backEMFChangeHandler
void backEMFChangeHandler(double back_emf) const
Definition: motor.cpp:197
phidgets::Motor::dutyCycleChangeHandler
void dutyCycleChangeHandler(double duty_cycle) const
Definition: motor.cpp:192
phidgets::Motor::setAcceleration
void setAcceleration(double acceleration) const
Definition: motor.cpp:127
phidgets::Motor::motor_handle_
PhidgetDCMotorHandle motor_handle_
Definition: motor.h:71
phidgets::Motor::channel_
int channel_
Definition: motor.h:68
phidgets::Motor
Definition: motor.h:41
phidgets::Motor::setDataInterval
void setDataInterval(uint32_t data_interval_ms) const
Definition: motor.cpp:152
phidgets::Motor::setBraking
void setBraking(double braking) const
Definition: motor.cpp:179
phidgets::Motor::getBraking
double getBraking() const
Definition: motor.cpp:164


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