Library for MAX14871 Shield, MAXREFDES89#
Dependents: MAXREFDES89_MAX14871_Shield_Demo MAXREFDES89_Test_Program Line_Following_Bot Line_Following_Bot_Pololu
Diff: max14871_shield.cpp
- Revision:
- 0:b5189f4ce1cb
- Child:
- 1:7e9b864ddacf
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/max14871_shield.cpp Thu Jul 23 23:36:46 2015 +0000 @@ -0,0 +1,501 @@ +/******************************************************************//** +* @file max14871_shield.h +* +* @author Justin Jordan +* +* @version 0.0 +* +* Started: 18JUL15 +* +* Updated: +* +* @brief Source file for Max14871_Shield class +*********************************************************************** +* Copyright (C) 2015 Maxim Integrated Products, Inc., All Rights Reserved. +* +* Permission is hereby granted, free of charge, to any person obtaining a +* copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation +* the rights to use, copy, modify, merge, publish, distribute, sublicense, +* and/or sell copies of the Software, and to permit persons to whom the +* Software is furnished to do so, subject to the following conditions: +* +* The above copyright notice and this permission notice shall be included +* in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS +* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF +* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. +* IN NO EVENT SHALL MAXIM INTEGRATED BE LIABLE FOR ANY CLAIM, DAMAGES +* OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, +* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR +* OTHER DEALINGS IN THE SOFTWARE. +* +* Except as contained in this notice, the name of Maxim Integrated +* Products, Inc. shall not be used except as stated in the Maxim Integrated +* Products, Inc. Branding Policy. +* +* The mere transfer of this software does not imply any licenses +* of trade secrets, proprietary technology, copyrights, patents, +* trademarks, maskwork rights, or any other form of intellectual +* property whatsoever. Maxim Integrated Products, Inc. retains all +* ownership rights. +**********************************************************************/ + + +#include "max14871_shield.h" + +#define MIN_PERIOD (20) //50KHz + +//Motor Driver control inputs +#define MD_EN (0x01) +#define MD_DIR (0x02) +#define MD_MODE0 (0x04) +#define MD_MODE1 (0x08) + +#define MAX_VREF (100) + +//GPIO Expander Default Configurations +#define MAX7300_ALL_OUTPUTS (0x55) +#define MAX7300_ALL_INPUTS (0xFF) +#define MAX7300_OUTPUT_DEFAULT (0xBB) + + +//********************************************************************* +Max14871_Shield::Max14871_Shield(I2C *i2c_bus, bool default_config): _p_i2c(i2c_bus) +{ + _i2c_owner = false; + + if(default_config) + { + _p_io_expander = new Max7300(_p_i2c, Max7300::MAX7300_I2C_ADRS0); + _p_digi_pot1 = new Max5387(_p_i2c, Max5387::MAX5387_I2C_ADRS0); + _p_digi_pot2 = new Max5387(_p_i2c, Max5387::MAX5387_I2C_ADRS1); + + _p_pwm1 = new PwmOut(D4); + _p_pwm2 = new PwmOut(D5); + _p_pwm3 = new PwmOut(D9); + _p_pwm4 = new PwmOut(D10); + } + else + { + _p_io_expander = new Max7300(_p_i2c, Max7300::MAX7300_I2C_ADRS1); + _p_digi_pot1 = new Max5387(_p_i2c, Max5387::MAX5387_I2C_ADRS2); + _p_digi_pot2 = new Max5387(_p_i2c, Max5387::MAX5387_I2C_ADRS3); + + _p_pwm1 = new PwmOut(D3); + _p_pwm2 = new PwmOut(D6); + _p_pwm3 = new PwmOut(D8); + _p_pwm4 = new PwmOut(D11); + } + + init_board(); +} + + +//********************************************************************* +Max14871_Shield::Max14871_Shield(PinName sda, PinName scl, bool default_config) +{ + _p_i2c = new I2C(sda, scl); + _i2c_owner = true; + + if(default_config) + { + _p_io_expander = new Max7300(_p_i2c, Max7300::MAX7300_I2C_ADRS0); + _p_digi_pot1 = new Max5387(_p_i2c, Max5387::MAX5387_I2C_ADRS0); + _p_digi_pot2 = new Max5387(_p_i2c, Max5387::MAX5387_I2C_ADRS1); + + _p_pwm1 = new PwmOut(D4); + _p_pwm2 = new PwmOut(D5); + _p_pwm3 = new PwmOut(D9); + _p_pwm4 = new PwmOut(D10); + } + else + { + _p_io_expander = new Max7300(_p_i2c, Max7300::MAX7300_I2C_ADRS1); + _p_digi_pot1 = new Max5387(_p_i2c, Max5387::MAX5387_I2C_ADRS2); + _p_digi_pot2 = new Max5387(_p_i2c, Max5387::MAX5387_I2C_ADRS3); + + _p_pwm1 = new PwmOut(D3); + _p_pwm2 = new PwmOut(D6); + _p_pwm3 = new PwmOut(D8); + _p_pwm4 = new PwmOut(D11); + } + + init_board(); +} + + +//********************************************************************* +Max14871_Shield::~Max14871_Shield() +{ + if(_i2c_owner) + { + delete _p_i2c; + } + + delete _p_io_expander; + delete _p_digi_pot1; + delete _p_digi_pot2; + delete _p_pwm1; + delete _p_pwm2; + delete _p_pwm3; + delete _p_pwm4; +} + + +//********************************************************************* +int16_t Max14871_Shield::set_operating_mode(max14871_motor_driver_t md, + max14871_operating_mode_t mode) +{ + int16_t result = 0; + int16_t port_data; + + Max7300::max7300_port_number_t low_port; + + //determine the low port of an 8 bit register to read/write + if(md < MD3) + { + low_port = Max7300::MAX7300_PORT_04; + } + else + { + low_port = Max7300::MAX7300_PORT_12; + } + + //get current state of outputs + port_data = _p_io_expander->read_8_ports(low_port); + + switch(mode) + { + //if(md % 2) for following cases, modify control bits + //of odd motor driver + + case COAST: + if(md % 2) + { + port_data |= MD_EN; + } + else + { + port_data |= (MD_EN << 4); + } + break; + + case BRAKE: + if(md % 2) + { + port_data &= ~MD_EN; + } + else + { + port_data &= ~(MD_EN << 4); + } + + set_pwm_duty_cycle(md, 0); + break; + + case REVERSE: + if(md % 2) + { + port_data &= ~(MD_EN + MD_DIR); + } + else + { + port_data &= ~((MD_EN + MD_DIR) << 4); + } + break; + + case FORWARD: + if(md % 2) + { + port_data &= ~MD_EN; + port_data |= MD_DIR; + } + else + { + port_data &= ~(MD_EN << 4); + port_data |= (MD_DIR << 4); + } + break; + + default: + result = -1; + break; + } + + if(!result) + { + //write data back to port + result = _p_io_expander->write_8_ports(low_port, (uint8_t) port_data); + } + + return result; +} + + +//********************************************************************* +int16_t Max14871_Shield::set_current_regulation_mode(max14871_motor_driver_t md, + max14871_current_regulation_mode_t mode, + uint8_t vref) +{ + int16_t result = 0; + int16_t port_data; + + Max7300::max7300_port_number_t low_port; + Max5387 *p_digi_pot; + + //determine the low port of an 8 bit register to read/write + if(md < MD3) + { + low_port = Max7300::MAX7300_PORT_04; + p_digi_pot = _p_digi_pot1; + } + else + { + low_port = Max7300::MAX7300_PORT_12; + p_digi_pot = _p_digi_pot2; + } + + //get current state of outputs + port_data = _p_io_expander->read_8_ports(low_port); + + switch(mode) + { + case RIPPLE_25_INTERNAL_REF: + if(md % 2) + { + port_data &= ~MD_MODE0; + port_data |= MD_MODE1; + p_digi_pot->write_ch_A(0); + } + else + { + port_data &= ~(MD_MODE0 << 4); + port_data |= (MD_MODE1 << 4); + p_digi_pot->write_ch_B(0); + } + break; + + case RIPPLE_25_EXTERNAL_REF: + if(md % 2) + { + port_data &= ~MD_MODE0; + port_data |= MD_MODE1; + + if(vref > MAX_VREF) + { + vref = MAX_VREF; + } + p_digi_pot->write_ch_A(vref); + } + else + { + port_data &= ~(MD_MODE0 << 4); + port_data |= (MD_MODE1 << 4); + + if(vref > MAX_VREF) + { + vref = MAX_VREF; + } + p_digi_pot->write_ch_B(vref); + } + break; + + case TCOFF_FAST_INTERNAL_REF: + if(md % 2) + { + port_data |= (MD_MODE1 + MD_MODE0); + p_digi_pot->write_ch_A(0); + } + else + { + port_data |= ((MD_MODE1 + MD_MODE0) << 4); + p_digi_pot->write_ch_B(0); + } + break; + + case TCOFF_SLOW_INTERNAL_REF: + if(md % 2) + { + port_data |= MD_MODE0; + port_data &= ~MD_MODE1; + p_digi_pot->write_ch_A(0); + } + else + { + port_data |= (MD_MODE0 << 4); + port_data &= ~(MD_MODE1 << 4); + p_digi_pot->write_ch_B(0); + } + break; + + case TCOFF_FAST_EXTERNAL_REF: + if(md % 2) + { + port_data |= (MD_MODE1 + MD_MODE0); + + if(vref > MAX_VREF) + { + vref = MAX_VREF; + } + p_digi_pot->write_ch_A(vref); + } + else + { + port_data |= ((MD_MODE1 + MD_MODE0) << 4); + + if(vref > MAX_VREF) + { + vref = MAX_VREF; + } + p_digi_pot->write_ch_B(vref); + } + break; + + case TCOFF_SLOW_EXTERNAL_REF: + if(md % 2) + { + port_data |= MD_MODE0; + port_data &= ~MD_MODE1; + + if(vref > MAX_VREF) + { + vref = MAX_VREF; + } + p_digi_pot->write_ch_A(vref); + } + else + { + port_data |= (MD_MODE0 << 4); + port_data &= ~(MD_MODE1 << 4); + + if(vref > MAX_VREF) + { + vref = MAX_VREF; + } + p_digi_pot->write_ch_B(vref); + } + break; + + default: + result = -1; + break; + } + + if(!result) + { + //write data back to port + result = _p_io_expander->write_8_ports(low_port, (uint8_t) port_data); + } + + return result; +} + + +//********************************************************************* +int16_t Max14871_Shield::set_pwm_period(max14871_motor_driver_t md, uint16_t period) +{ + int16_t result = 0; + + if(period < MIN_PERIOD) + { + result = -1; + } + else + { + switch(md) + { + case MD1: + _p_pwm1->period_us(period); + break; + + case MD2: + _p_pwm2->period_us(period); + break; + + case MD3: + _p_pwm3->period_us(period); + break; + + case MD4: + _p_pwm4->period_us(period); + break; + + default: + result = -1; + break; + } + } + + return result; +} + + +//********************************************************************* +int16_t Max14871_Shield::set_pwm_duty_cycle(max14871_motor_driver_t md, uint16_t duty_cycle) +{ + int16_t result = 0; + + switch(md) + { + case MD1: + _p_pwm1->pulsewidth_us(duty_cycle); + break; + + case MD2: + _p_pwm2->pulsewidth_us(duty_cycle); + break; + + case MD3: + _p_pwm3->pulsewidth_us(duty_cycle); + break; + + case MD4: + _p_pwm4->pulsewidth_us(duty_cycle); + break; + + default: + result = -1; + break; + } + + return result; +} + + +//********************************************************************* +void Max14871_Shield::init_board(void) +{ + //configure these ports as outputs + _p_io_expander->config_4_ports(Max7300::MAX7300_PORT_04, MAX7300_ALL_OUTPUTS); + _p_io_expander->config_4_ports(Max7300::MAX7300_PORT_08, MAX7300_ALL_OUTPUTS); + _p_io_expander->config_4_ports(Max7300::MAX7300_PORT_12, MAX7300_ALL_OUTPUTS); + _p_io_expander->config_4_ports(Max7300::MAX7300_PORT_16, MAX7300_ALL_OUTPUTS); + + //Set /EN and DIR pin of all motor drivers and set mode pin + //of all motor drivers to 0.75V + _p_io_expander->write_8_ports(Max7300::MAX7300_PORT_04, MAX7300_OUTPUT_DEFAULT); + _p_io_expander->write_8_ports(Max7300::MAX7300_PORT_12, MAX7300_OUTPUT_DEFAULT); + + //configure these ports as inputs w/pull-up, + _p_io_expander->config_4_ports(Max7300::MAX7300_PORT_20, MAX7300_ALL_INPUTS); + _p_io_expander->config_4_ports(Max7300::MAX7300_PORT_24, MAX7300_ALL_INPUTS); + _p_io_expander->config_4_ports(Max7300::MAX7300_PORT_28, MAX7300_ALL_INPUTS); + + //config port 31 as output for interrupt + _p_io_expander->config_port(Max7300::MAX7300_PORT_31, Max7300::MAX7300_PORT_OUTPUT); + + _p_io_expander->enable_transition_detection(); + _p_io_expander->enable_ports(); + + //set Vref pin of all motor drivers to 1.3V + _p_digi_pot1->write_ch_AB(MAX_VREF); + _p_digi_pot2->write_ch_AB(MAX_VREF); + + //set switching frequency of all motor drivers to 50KHz + _p_pwm1->period_us(MIN_PERIOD); + _p_pwm2->period_us(MIN_PERIOD); + _p_pwm3->period_us(MIN_PERIOD); + _p_pwm4->period_us(MIN_PERIOD); +}