This class library has been created for use with the Apeiros Robot by Abe Howell's Robotics.
Apeiros Class Reference
#include <Apeiros.h>
Public Member Functions | |
| Apeiros (PinName tx, PinName rx, int leftMotorPwmOffset, int rightMotorPwmOffset) | |
| Create Apeiros instance. | |
| void | Begin (void) |
| Begin using Apeiros class. | |
| bool | IsSerialDataAvailable (void) |
| Is Serial data available to be parsed. | |
| void | ParseUartData (void) |
| Parse available serial UART data. | |
| void | SetBuzzerTone (int buzzerTone) |
| Set piezo buzzer tone. | |
| void | SetMotorSpeed (int leftMotorSpeed, int rightMotorSpeed) |
| Set left and right motor speeds. | |
| void | SetGripperPosition (int pulseWidth_us) |
| Set servo gripper position. | |
| int | GetLeftEncoder (void) |
| Return integer count for left wheel encoder. | |
| int | GetRightEncoder (void) |
| Return integer count for right wheel encoder. | |
| void | ResetWheelEncoders (void) |
| Reset both left & right wheel encoder counts. | |
Data Fields | |
| DigitalIn | leftFrontIR |
| DigitalIn object for Left Front IR Sensor. | |
| DigitalIn | centerFrontIR |
| DigitalIn object for Center Front IR Sensor. | |
| DigitalIn | rightFrontIR |
| DigitalIn object for Right Front IR Sensor. | |
| DigitalIn | leftRearIR |
| DigitalIn object for Left Rear IR Sensor. | |
| DigitalIn | rightRearIR |
| DigitalIn object for Right Rear IR Sensor. | |
| AnalogIn | ad_0 |
| ad_0 AnalogIn object. | |
| AnalogIn | ad_1 |
| ad_1 AnalogIn object. | |
| AnalogIn | ad_2 |
| ad_2 AnalogIn object. | |
| AnalogIn | ad_3 |
| ad_3 AnalogIn object. | |
| AnalogIn | ad_4 |
| ad_4 AnalogIn object. | |
| AnalogIn | ad_5 |
| ad_5 AnalogIn object. | |
Detailed Description
Create Apeiros class.
- Parameters:
-
Apeiros class
Definition at line 48 of file Apeiros.h.
Constructor & Destructor Documentation
| Apeiros | ( | PinName | tx, |
| PinName | rx, | ||
| int | leftMotorPwmOffset, | ||
| int | rightMotorPwmOffset | ||
| ) |
Create Apeiros instance.
- Parameters:
-
tx specified as PinName of UART Tx pin. Use SERIAL_TX as default. Use PA_9 for wireless shield. rx specified as PinName of UART Rx pin. Use SERIAL_RX as deafult. Use PA_10 for wireless shield. leftMotorPwmOffset specified as integer value from 0-150. Use 100 as default. rightMotorPwmOffset specified as integer value from 0-150. Use 100 as default.
The PwmOffsets are used to eliminate the deadband for both the left & right motor, so that each motor begins to rotate when motor speeds are specified as aperiros.SetMotorSpeed(1,1).
Pass a zero for each PwmOffset parameter and then use SetMotorSpeed function to find the leftMotorPwmOffset & rightMotorPwmOffset values.
You have found the PwmOffset value when the respective motor goes from not rotating to starting rotation.
Definition at line 7 of file Apeiros.cpp.
Member Function Documentation
| void Begin | ( | void | ) |
Begin using Apeiros class.
Must be called before using class functions.
Definition at line 63 of file Apeiros.cpp.
| int GetLeftEncoder | ( | void | ) |
Return integer count for left wheel encoder.
- Returns:
- Integer value for left wheel encoder count.
Definition at line 545 of file Apeiros.cpp.
| int GetRightEncoder | ( | void | ) |
Return integer count for right wheel encoder.
- Returns:
- Integer value for right wheel encoder count.
Definition at line 553 of file Apeiros.cpp.
| bool IsSerialDataAvailable | ( | void | ) |
Is Serial data available to be parsed.
- Returns:
- 1 if serial data is available, 0 if no serial data has been received
Definition at line 235 of file Apeiros.cpp.
| void ParseUartData | ( | void | ) |
Parse available serial UART data.
Definition at line 244 of file Apeiros.cpp.
| void ResetWheelEncoders | ( | void | ) |
Reset both left & right wheel encoder counts.
Definition at line 561 of file Apeiros.cpp.
| void SetBuzzerTone | ( | int | buzzerTone ) |
Set piezo buzzer tone.
- Parameters:
-
buzzerTone specified as an integer value(int) from 0-100.
Definition at line 307 of file Apeiros.cpp.
| void SetGripperPosition | ( | int | pulseWidth_us ) |
Set servo gripper position.
- Parameters:
-
pulseWidth_us specified as an integer value(int) from MIN_GRIPPER_PULSE(1000) to MAX_GRIPPER_PULSE(2200).
Definition at line 534 of file Apeiros.cpp.
| void SetMotorSpeed | ( | int | leftMotorSpeed, |
| int | rightMotorSpeed | ||
| ) |
Set left and right motor speeds.
- Parameters:
-
leftMotorSpeed specified as an integer value(int) from 0 to (255-leftMotorPwmOffset). Use a preceeding negative sign to reverse motor rotation. rightMotorSpeed specified as an integer value(int) from 0 to (255-rightMotorPwmOffset). Use a preceeding negative sign to reverse motor rotation.
For example, if leftMotorPwmOffset = 95 then valid left motor speed range is 0 to 165. Use a preceeding negative sign to reverse motor rotation.
Drive robot forward with apeiros.SetMotorSpeed(65,65).
Drive robot in reverse with apeiros.SetMotorSpeed(-65,-65).
Spin robot clockwise with apeiros.SetMotorSpeed(65,-65).
Spin robot counterclockwise with apeiros.SetMotorSpeed(-65,65).
Definition at line 362 of file Apeiros.cpp.
Field Documentation
| AnalogIn ad_0 |
| AnalogIn ad_1 |
| AnalogIn ad_2 |
| AnalogIn ad_3 |
| AnalogIn ad_4 |
| AnalogIn ad_5 |
| DigitalIn centerFrontIR |
| DigitalIn leftFrontIR |
| DigitalIn leftRearIR |
| DigitalIn rightFrontIR |
| DigitalIn rightRearIR |
Generated on Fri Jul 15 2022 01:40:07 by
1.7.2