#include <WickedMotorShield.h>
|
static uint32_t | getRCIN (uint8_t rc_input_number, uint32_t timeout=0) |
|
static uint8_t | version (void) |
|
Definition at line 197 of file WickedMotorShield.h.
◆ WickedMotorShield()
WickedMotorShield::WickedMotorShield |
( |
uint8_t |
use_alternate_pins = 0 | ) |
|
◆ apply_mask()
void WickedMotorShield::apply_mask |
( |
uint8_t * |
shift_register_value, |
|
|
uint8_t |
mask, |
|
|
uint8_t |
operation |
|
) |
| |
|
protected |
Carry out bitwise or/and operation .
- Parameters
-
shift_register_value | Address of shift register to be altered. This will be the address of either WickedDeviceShield::first_shift_register or WickedDeviceShield::second_shift_register. Only the bit whose location is given by the mask parameter will be altered. |
mask | with bit set in position to be changed. |
operation | flag indicating whether bit to be set (OPERATION_SET) or cleared (OPERATION_CLEAR). A value of OPERATION_NONE indicates that no action is to be taken. |
If operation clear do a bitwise and operation on the shift register byte and the mask with all bits inverted. In the inverted mask, the bit to be cleared is 0 and the other bits are 1.
If operation set do a bitwise or operation on the shift register byte and the mask. The mask has a one in the bit of the shift register to be set to be set.
Definition at line 236 of file WickedMotorShield.cpp.
◆ filter_mask()
uint8_t WickedMotorShield::filter_mask |
( |
uint8_t |
shift_register_value, |
|
|
uint8_t |
mask |
|
) |
| |
|
protected |
Apply a mask to an eight bit integer using bitwise and.
- Parameters
-
shift_register_value | byte to which mask is to be applied |
mask | byte containing mask to be applied |
- Returns
- 0 if bit indicated by mask is 0, otherwise return 1
Definition at line 255 of file WickedMotorShield.cpp.
◆ get_motor_brakeM()
uint8_t WickedMotorShield::get_motor_brakeM |
( |
uint8_t |
motor_number | ) |
|
|
protected |
Return motor brake status for a specific motor.
- Parameters
-
motor_number | integer representing motor |
- Returns
- shift register value for motor having done a bitwise and operation with the brake mask for the motor. This will be zero if the brake bit is not set and greater than zero if the brake bit is set.
Definition at line 493 of file WickedMotorShield.cpp.
◆ get_motor_directionM()
uint8_t WickedMotorShield::get_motor_directionM |
( |
uint8_t |
motor_number | ) |
|
|
protected |
Return motor direction for a specific motor.
- Parameters
-
motor_number | integer representing motor |
- Returns
- shift register value for motor having done a bitwise and operation with the direction mask for the motor. Value will zero if direction bit is set (counter clockwise). Otherwise it will be greater than zero if direction bit is not set (clockwise).
Definition at line 464 of file WickedMotorShield.cpp.
◆ get_rc_input_pin()
uint8_t WickedMotorShield::get_rc_input_pin |
( |
uint8_t |
rc_input_number | ) |
|
|
staticprivate |
◆ get_shift_register_value()
uint8_t WickedMotorShield::get_shift_register_value |
( |
uint8_t |
motor_number | ) |
|
|
protected |
Get the shift register information for a specific motor.
- Parameters
-
motor_number | Number of motor for which information is desired. |
The information for motors M1 to M4 are contained in the first shift register. The information for motors M5 and M6 is contained in the second shift register.
Definition at line 195 of file WickedMotorShield.cpp.
◆ getRCIN()
uint32_t WickedMotorShield::getRCIN |
( |
uint8_t |
rc_input_number, |
|
|
uint32_t |
timeout = 0 |
|
) |
| |
|
static |
◆ load_shift_register()
void WickedMotorShield::load_shift_register |
( |
void |
| ) |
|
|
protected |
Load the contents of second_shift_register and first_shift_register to the motor shield using SERIAL_LATCH_PIN, SERIAL_DATA_PIN, and SERIAL_CLOCK_PIN pins.
Data is only moved from the memory values on the Arduino board to the motor shield. No data is moved in the other direction.
Definition at line 181 of file WickedMotorShield.cpp.
◆ set_shift_register_value()
void WickedMotorShield::set_shift_register_value |
( |
uint8_t |
motor_number, |
|
|
uint8_t |
value |
|
) |
| |
|
protected |
Copy the shift register data for the specified motor into the correct data structure.
- Parameters
-
motor_number | number of motor for which data has been modified. |
value | information to be moved to shift register. |
Definition at line 209 of file WickedMotorShield.cpp.
◆ setBrakeData()
void WickedMotorShield::setBrakeData |
( |
uint8_t |
motor_number, |
|
|
uint8_t |
brake_type |
|
) |
| |
|
protected |
◆ setDirectionData()
void WickedMotorShield::setDirectionData |
( |
uint8_t |
motor_number, |
|
|
uint8_t |
direction |
|
) |
| |
|
protected |
Set the value for the direction in Mx_DIR_MASK bit and the element of the old_dir directory.
- Parameters
-
motor_number | number of motor for which direction is to be set |
direction | value to be set for direction (DIR_CW or DIR_CCW). The value of DIR_CW is 1 while the value for DIR_CCW is set to 0. |
Change Jan, 2020 - No action to be taken if brake bit is set.
This needs to be reviewed. Either the brake status should be set to BRAKE_OFF when the direction is set or no action should be taken if the brake status is not BRAKE_OFF. Should the brake status always be changed to BRAKE_OFF if this method is called.
Definition at line 328 of file WickedMotorShield.cpp.
◆ setSpeedM()
void WickedMotorShield::setSpeedM |
( |
uint8_t |
motor_number, |
|
|
uint8_t |
pwm_val |
|
) |
| |
|
protected |
◆ version()
uint8_t WickedMotorShield::version |
( |
void |
| ) |
|
|
static |
◆ first_shift_register
uint8_t WickedMotorShield::first_shift_register = 0xff |
|
staticprivate |
◆ M1_PWM_PIN
uint8_t WickedMotorShield::M1_PWM_PIN = 11 |
|
staticprotected |
Digital pin for M1 PWM (pulse width modulation).
Pin 11 for standard pins, use pin 8 for alternate pins.
Definition at line 210 of file WickedMotorShield.h.
◆ M6_PWM_PIN
uint8_t WickedMotorShield::M6_PWM_PIN = 3 |
|
staticprotected |
Digital pin for M6 PWM (pulse width modulation).
Pin 3 for standard pins, pin 4 for alternate pins.
Definition at line 215 of file WickedMotorShield.h.
◆ old_dir
uint8_t WickedMotorShield::old_dir = {0,0,0,0,0,0} |
|
staticprotected |
Contains the old value of the direction bit if the value of the brake bit is changed from 0 to 1.
When the brake bit is changed from 0 to 1, the direction bit indicates whether it is BRAKE_SOFT or BRAKE_HARD. If the direction bit wasn't copied to this array, the value would be lost.
Definition at line 216 of file WickedMotorShield.h.
◆ RCIN1_PIN
uint8_t WickedMotorShield::RCIN1_PIN = 4 |
|
staticprivate |
Digital pin used for Radio Control Input Pin 1.
Pin 4 used for standard pins, pin 3 for alternate pins.
Definition at line 202 of file WickedMotorShield.h.
◆ RCIN2_PIN
uint8_t WickedMotorShield::RCIN2_PIN = 8 |
|
staticprivate |
Digital pin used for Radio Control Input Pin 2.
Pin 8 used for standard pins, pin 11 for alternate pins.
Definition at line 203 of file WickedMotorShield.h.
◆ second_shift_register
uint8_t WickedMotorShield::second_shift_register = 0xff |
|
staticprivate |
◆ SERIAL_DATA_PIN
uint8_t WickedMotorShield::SERIAL_DATA_PIN = 12 |
|
staticprivate |
Digital Arduino pin used to send data to motor shield.
Pin 12 for standard pins, pin 0 for alternate pins.
Definition at line 201 of file WickedMotorShield.h.
The documentation for this class was generated from the following files: