USBInterface.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Osnabrueck University
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  * * Redistributions of source code must retain the above copyright notice,
00009  *   this list of conditions and the following disclaimer.
00010  * * Redistributions in binary form must reproduce the above copyright notice,
00011  *   this list of conditions and the following disclaimer in the documentation
00012  *   and/or other materials provided with the distribution.
00013  * * Neither the name of the Osnabrueck University nor the names of its
00014  *   contributors may be used to endorse or promote products derived from this
00015  *   software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00037 #ifndef USBINTERFACE_H_
00038 #define USBINTERFACE_H_
00039 
00040 #include <libusb.h>
00041 #include <list>
00042 #include <string>
00043 #include <cmath>
00044 #include <cstdint>
00045 #include <unistd.h>
00046 
00047 using std::string;
00048 using std::fabs;
00049 
00050 enum ChannelMode
00051 {
00052     Servo=0,
00053     ServoMultiplied=1,
00054     Output=2,
00055     Input = 3,
00056 };
00057 
00058 enum HomeMode
00059 {
00060     Off=0,
00061     Ignore=1,
00062     Goto=2
00063 };
00064 
00065 
00071 enum uscSerialMode
00072 {
00075     SERIAL_MODE_USB_DUAL_PORT = 0,
00076 
00081     SERIAL_MODE_USB_CHAINED = 1,
00082 
00089     SERIAL_MODE_UART_DETECT_BAUD_RATE = 2,
00090 
00097     SERIAL_MODE_UART_FIXED_BAUD_RATE = 3,
00098 };
00099 
00100 
00101 enum uscRequest
00102 {
00103     REQUEST_GET_PARAMETER = 0x81,
00104     REQUEST_SET_PARAMETER = 0x82,
00105     REQUEST_GET_VARIABLES = 0x83,
00106     REQUEST_SET_SERVO_VARIABLE = 0x84,
00107     REQUEST_SET_TARGET = 0x85,
00108     REQUEST_CLEAR_ERRORS = 0x86,
00109     REQUEST_GET_SERVO_SETTINGS = 0x87,
00110 
00111     // GET STACK and GET CALL STACK are only used on the Mini Maestro.
00112     REQUEST_GET_STACK = 0x88,
00113     REQUEST_GET_CALL_STACK = 0x89,
00114     REQUEST_SET_PWM = 0x8A,
00115 
00116     REQUEST_REINITIALIZE = 0x90,
00117     REQUEST_ERASE_SCRIPT = 0xA0,
00118     REQUEST_WRITE_SCRIPT = 0xA1,
00119     REQUEST_SET_SCRIPT_DONE = 0xA2, // value.low.b is 0 for go, 1 for stop, 2 for single-step
00120     REQUEST_RESTART_SCRIPT_AT_SUBROUTINE = 0xA3,
00121     REQUEST_RESTART_SCRIPT_AT_SUBROUTINE_WITH_PARAMETER = 0xA4,
00122     REQUEST_RESTART_SCRIPT = 0xA5,
00123     REQUEST_START_BOOTLOADER = 0xFF
00124 };
00125 
00126 
00132 struct channelSetting
00133 {
00134     channelSetting()
00135     {
00136         name = "";
00137         mode = ChannelMode::Servo;
00138         homeMode = HomeMode::Off;
00139         home = 6000;
00140         minimum = 3968;
00141         maximum = 8000;
00142         neutral = 6000;
00143         range = 1905;
00144         speed = 0;
00145         acceleration = 0;
00146     }
00147 
00148 
00152     string name;
00153 
00157     ChannelMode mode;
00158 
00162     HomeMode homeMode;
00163 
00171     uint16_t home;
00172 
00176     uint16_t minimum;
00177 
00181     uint16_t maximum;
00182 
00188     uint16_t neutral;
00189 
00199     uint16_t range;
00200 
00212     uint16_t speed;
00213 
00220     uint8_t acceleration;
00221 };
00222 
00223 
00224 struct uscSettings
00225 {
00226     uscSettings()
00227     {
00228         servosAvailable = 6;
00229         servoPeriod = 156;
00230         miniMaestroServoPeriod = 80000;
00231         servoMultiplier = 1;
00232         serialMode = uscSerialMode::SERIAL_MODE_UART_DETECT_BAUD_RATE;
00233         fixedBaudRate = 9600;
00234         enableCrc = false;
00235         neverSuspend = false;
00236         serialDeviceNumber = 12;
00237         miniSscOffset = 0;
00238         serialTimeout = 0;
00239         scriptDone = true;
00240         enablePullups = false;
00241     }
00242 
00243 
00248     uint8_t servosAvailable;
00249 
00263     uint8_t  servoPeriod;
00264 
00276     uint32_t miniMaestroServoPeriod;
00277 
00285     uint16_t servoMultiplier;
00286 
00291     uscSerialMode serialMode;
00292 
00307     uint32_t fixedBaudRate;
00308 
00313     bool enableCrc;
00314 
00320     bool neverSuspend;
00321 
00326     uint8_t serialDeviceNumber;
00327 
00334     uint8_t miniSscOffset;
00335 
00340     uint16_t serialTimeout;
00341 
00346     bool scriptDone;
00347 
00352     std::list<channelSetting> channelSettings;
00353 
00361     bool enablePullups;
00362 };
00363 
00364 struct servoStatus
00365 {
00367     uint16_t position;
00368 
00370     uint16_t target;
00371 
00373     uint16_t speed;
00374 
00376     uint8_t acceleration;
00377 };
00378 
00379 struct maestroStatus
00380 {
00384     uint8_t stackPointer;
00385 
00389     uint8_t callStackPointer;
00390 
00396     uint16_t errors;
00397 
00401     uint16_t programCounter;
00402 
00405     int16_t buffer[3];
00406 
00411     int16_t stack[32];
00412 
00418     uint16_t callStack[10];
00419 
00426     uint8_t scriptDone;
00427 
00430     uint8_t buffer2;
00431 };
00432 
00437 enum uscParameter
00438 {
00439     PARAMETER_INITIALIZED = 0, // 1 byte - 0 or 0xFF
00440     PARAMETER_SERVOS_AVAILABLE = 1, // 1 byte - 0-5
00441     PARAMETER_SERVO_PERIOD = 2, // 1 byte - ticks allocated to each servo/256
00442     PARAMETER_SERIAL_MODE = 3, // 1 byte unsigned value.  Valid values are SERIAL_MODE_*.  Init variable.
00443     PARAMETER_SERIAL_FIXED_BAUD_RATE = 4, // 2-byte unsigned value; 0 means autodetect.  Init parameter.
00444     PARAMETER_SERIAL_TIMEOUT = 6, // 2-byte unsigned value
00445     PARAMETER_SERIAL_ENABLE_CRC = 8, // 1 byte boolean value
00446     PARAMETER_SERIAL_NEVER_SUSPEND = 9, // 1 byte boolean value
00447     PARAMETER_SERIAL_DEVICE_NUMBER = 10, // 1 byte unsigned value, 0-127
00448     PARAMETER_SERIAL_BAUD_DETECT_TYPE = 11, // 1 byte value
00449 
00450     PARAMETER_IO_MASK_C = 16, // 1 byte - pins used for I/O instead of servo
00451     PARAMETER_OUTPUT_MASK_C = 17, // 1 byte - outputs that are enabled
00452 
00453     PARAMETER_CHANNEL_MODES_0_3                 = 12, // 1 byte - channel modes 0-3
00454     PARAMETER_CHANNEL_MODES_4_7                 = 13, // 1 byte - channel modes 4-7
00455     PARAMETER_CHANNEL_MODES_8_11                = 14, // 1 byte - channel modes 8-11
00456     PARAMETER_CHANNEL_MODES_12_15               = 15, // 1 byte - channel modes 12-15
00457     PARAMETER_CHANNEL_MODES_16_19               = 16, // 1 byte - channel modes 16-19
00458     PARAMETER_CHANNEL_MODES_20_23               = 17, // 1 byte - channel modes 20-23
00459     PARAMETER_MINI_MAESTRO_SERVO_PERIOD_L = 18, // servo period: 3-byte unsigned values, units of quarter microseconds
00460     PARAMETER_MINI_MAESTRO_SERVO_PERIOD_HU = 19,
00461     PARAMETER_ENABLE_PULLUPS = 21,  // 1 byte: 0 or 1
00462     PARAMETER_SCRIPT_CRC = 22, // 2 bytes - stores a checksum of the bytecode program, for comparison
00463     PARAMETER_SCRIPT_DONE = 24, // 1 byte - copied to scriptDone on startup
00464     PARAMETER_SERIAL_MINI_SSC_OFFSET = 25, // 1 byte (0-254)
00465     PARAMETER_SERVO_MULTIPLIER = 26, // 1 byte (0-255)
00466 
00467     // 9 * 24 = 216, so we can safely start at 30
00468     PARAMETER_SERVO0_HOME = 30, // 2 byte home position (0=off; 1=ignore)
00469     PARAMETER_SERVO0_MIN = 32, // 1 byte min allowed value (x2^6)
00470     PARAMETER_SERVO0_MAX = 33, // 1 byte max allowed value (x2^6)
00471     PARAMETER_SERVO0_NEUTRAL = 34, // 2 byte neutral position
00472     PARAMETER_SERVO0_RANGE = 36, // 1 byte range
00473     PARAMETER_SERVO0_SPEED = 37, // 1 byte (5 mantissa,3 exponent) us per 10ms
00474     PARAMETER_SERVO0_ACCELERATION = 38, // 1 byte (speed changes that much every 10ms)
00475     PARAMETER_SERVO1_HOME = 39, // 2 byte home position (0=off; 1=ignore)
00476     PARAMETER_SERVO1_MIN = 41, // 1 byte min allowed value (x2^6)
00477     PARAMETER_SERVO1_MAX = 42, // 1 byte max allowed value (x2^6)
00478     PARAMETER_SERVO1_NEUTRAL = 43, // 2 byte neutral position
00479     PARAMETER_SERVO1_RANGE = 45, // 1 byte range
00480     PARAMETER_SERVO1_SPEED = 46, // 1 byte (5 mantissa,3 exponent) us per 10ms
00481     PARAMETER_SERVO1_ACCELERATION = 47, // 1 byte (speed changes that much every 10ms)
00482     PARAMETER_SERVO2_HOME = 48, // 2 byte home position (0=off; 1=ignore)
00483     PARAMETER_SERVO2_MIN = 50, // 1 byte min allowed value (x2^6)
00484     PARAMETER_SERVO2_MAX = 51, // 1 byte max allowed value (x2^6)
00485     PARAMETER_SERVO2_NEUTRAL = 52, // 2 byte neutral position
00486     PARAMETER_SERVO2_RANGE = 54, // 1 byte range
00487     PARAMETER_SERVO2_SPEED = 55, // 1 byte (5 mantissa,3 exponent) us per 10ms
00488     PARAMETER_SERVO2_ACCELERATION = 56, // 1 byte (speed changes that much every 10ms)
00489     PARAMETER_SERVO3_HOME = 57, // 2 byte home position (0=off; 1=ignore)
00490     PARAMETER_SERVO3_MIN = 59, // 1 byte min allowed value (x2^6)
00491     PARAMETER_SERVO3_MAX = 60, // 1 byte max allowed value (x2^6)
00492     PARAMETER_SERVO3_NEUTRAL = 61, // 2 byte neutral position
00493     PARAMETER_SERVO3_RANGE = 63, // 1 byte range
00494     PARAMETER_SERVO3_SPEED = 64, // 1 byte (5 mantissa,3 exponent) us per 10ms
00495     PARAMETER_SERVO3_ACCELERATION = 65, // 1 byte (speed changes that much every 10ms)
00496     PARAMETER_SERVO4_HOME = 66, // 2 byte home position (0=off; 1=ignore)
00497     PARAMETER_SERVO4_MIN = 68, // 1 byte min allowed value (x2^6)
00498     PARAMETER_SERVO4_MAX = 69, // 1 byte max allowed value (x2^6)
00499     PARAMETER_SERVO4_NEUTRAL = 70, // 2 byte neutral position
00500     PARAMETER_SERVO4_RANGE = 72, // 1 byte range
00501     PARAMETER_SERVO4_SPEED = 73, // 1 byte (5 mantissa,3 exponent) us per 10ms
00502     PARAMETER_SERVO4_ACCELERATION = 74, // 1 byte (speed changes that much every 10ms)
00503     PARAMETER_SERVO5_HOME = 75, // 2 byte home position (0=off; 1=ignore)
00504     PARAMETER_SERVO5_MIN = 77, // 1 byte min allowed value (x2^6)
00505     PARAMETER_SERVO5_MAX = 78, // 1 byte max allowed value (x2^6)
00506     PARAMETER_SERVO5_NEUTRAL = 79, // 2 byte neutral position
00507     PARAMETER_SERVO5_RANGE = 81, // 1 byte range
00508     PARAMETER_SERVO5_SPEED = 82, // 1 byte (5 mantissa,3 exponent) us per 10ms
00509     PARAMETER_SERVO5_ACCELERATION = 83, // 1 byte (speed changes that much every 10ms)
00510 };
00511 
00512 
00513 const uint8_t servoParameterBytes = 9;
00514 
00515 
00516 class USBPololuInterface
00517 {
00518 public:
00519     USBPololuInterface(uint16_t vendorID = 8187, uint16_t productID = 137);
00520     ~USBPololuInterface();
00521 
00522     void setTarget(int servo, ushort value);
00523     void setSpeed(int servo, ushort value);
00524     void moveToTarget(int servo, ushort value);
00525     void moveToTarget(int servo, ushort value, ushort time);
00526     void getServoStatus(int servo, servoStatus& status);
00527 
00528     void setUscSettings(uscSettings settings);
00529 
00530     static int MOVE_TARGET_TIMEOUT;
00531     static int MOVE_TARGET_MAX_TRYS;
00532 private:
00533 
00534     void controlTransfer(char requestType, char request, ushort value, ushort index);
00535     void controlTransfer(char requestType, char request, ushort Value, ushort Index, unsigned char * data, ushort length);
00536 
00537 
00538     uscParameter    specifyServo(uscParameter p, uint8_t servo);
00539     void            setRawParameter(ushort parameter, ushort value, int bytes);
00540     uint8_t         channelToPort(uint8_t channel);
00541     uint8_t         normalSpeedToExponentialSpeed(ushort normalSpeed);
00542 
00543     string getErrorDescription(int code);
00544     libusb_device*              m_device;
00545     libusb_context*             m_context;
00546     libusb_device_handle*       m_deviceHandle;
00547 
00548 };
00549 
00550 
00551 #endif /* USBINTERFACE_H_ */


kurt3d
Author(s): Thomas Wiemann, Benjamin Kisliuk, Alexander Mock
autogenerated on Wed Sep 16 2015 10:24:29