motors.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 
33 #include <libphidget22/phidget22.h>
34 
35 #include "phidgets_api/motors.h"
36 #include "phidgets_api/phidget22.h"
37 
38 namespace phidgets {
39 
40 Motors::Motors(int32_t serial_number, int hub_port, bool is_hub_port_device,
41  std::function<void(int, double)> duty_cycle_change_handler,
42  std::function<void(int, double)> back_emf_change_handler)
43 {
44  PhidgetReturnCode ret;
45 
46  PhidgetDCMotorHandle motor_handle;
47 
48  ret = PhidgetDCMotor_create(&motor_handle);
49  if (ret != EPHIDGET_OK)
50  {
51  throw Phidget22Error(
52  "Failed to create Motor handle for determining channel "
53  "count",
54  ret);
55  }
56 
57  PhidgetHandle handle = reinterpret_cast<PhidgetHandle>(motor_handle);
58 
59  helpers::openWaitForAttachment(handle, serial_number, hub_port,
60  is_hub_port_device, 0);
61 
62  ret = Phidget_getDeviceChannelCount(handle, PHIDCHCLASS_DCMOTOR,
63  &motor_count_);
64 
65  helpers::closeAndDelete(&handle);
66 
67  if (ret != EPHIDGET_OK)
68  {
69  throw Phidget22Error("Failed to get Motor device channel count", ret);
70  }
71 
72  motors_.resize(motor_count_);
73  for (uint32_t i = 0; i < motor_count_; ++i)
74  {
75  motors_[i] = std::make_unique<Motor>(
76  serial_number, hub_port, is_hub_port_device, i,
77  duty_cycle_change_handler, back_emf_change_handler);
78  }
79 }
80 
82 {
83 }
84 
85 uint32_t Motors::getMotorCount() const noexcept
86 {
87  return motor_count_;
88 }
89 
90 double Motors::getDutyCycle(int index) const
91 {
92  return motors_.at(index)->getDutyCycle();
93 }
94 
95 void Motors::setDutyCycle(int index, double duty_cycle) const
96 {
97  motors_.at(index)->setDutyCycle(duty_cycle);
98 }
99 
100 double Motors::getAcceleration(int index) const
101 {
102  return motors_.at(index)->getAcceleration();
103 }
104 
105 void Motors::setAcceleration(int index, double acceleration) const
106 {
107  motors_.at(index)->setAcceleration(acceleration);
108 }
109 
110 double Motors::getBackEMF(int index) const
111 {
112  return motors_.at(index)->getBackEMF();
113 }
114 
115 void Motors::setDataInterval(int index, uint32_t data_interval_ms) const
116 {
117  motors_.at(index)->setDataInterval(data_interval_ms);
118 }
119 
120 double Motors::getBraking(int index) const
121 {
122  return motors_.at(index)->getBraking();
123 }
124 
125 void Motors::setBraking(int index, double braking) const
126 {
127  motors_.at(index)->setBraking(braking);
128 }
129 
130 } // namespace phidgets
phidgets
Definition: accelerometer.h:39
phidgets::Motors::setDutyCycle
void setDutyCycle(int index, double duty_cycle) const
Definition: motors.cpp:95
phidgets::Motors::~Motors
~Motors()
Definition: motors.cpp:81
phidgets::Motors::getMotorCount
uint32_t getMotorCount() const noexcept
Definition: motors.cpp:85
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::Motors::setAcceleration
void setAcceleration(int index, double acceleration) const
Definition: motors.cpp:105
phidgets::Motors::setBraking
void setBraking(int index, double braking) const
Definition: motors.cpp:125
phidgets::helpers::closeAndDelete
void closeAndDelete(PhidgetHandle *handle) noexcept
Definition: phidget22.cpp:93
phidgets::Motors::Motors
Motors(int32_t serial_number, int hub_port, bool is_hub_port_device, std::function< void(int, double)> duty_cycle_change_handler, std::function< void(int, double)> back_emf_change_handler)
Definition: motors.cpp:40
phidget22.h
phidgets::Motors::motor_count_
uint32_t motor_count_
Definition: motors.h:66
phidgets::Phidget22Error
Definition: phidget22.h:46
phidgets::Motors::getAcceleration
double getAcceleration(int index) const
Definition: motors.cpp:100
phidgets::Motors::motors_
std::vector< std::unique_ptr< Motor > > motors_
Definition: motors.h:67
phidgets::Motors::setDataInterval
void setDataInterval(int index, uint32_t data_interval_ms) const
Definition: motors.cpp:115
phidgets::Motors::getBraking
double getBraking(int index) const
Definition: motors.cpp:120
phidgets::Motors::getBackEMF
double getBackEMF(int index) const
Definition: motors.cpp:110
motors.h
phidgets::Motors::getDutyCycle
double getDutyCycle(int index) const
Definition: motors.cpp:90


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