Andrea Campanella / ArduinoMotorShield

Fork of ArduinoMotorShield by John Bailey

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers ArduinoMotorShield.cpp Source File

ArduinoMotorShield.cpp

00001 /** 
00002 
00003 Copyright 2014 John Bailey
00004    
00005 Licensed under the Apache License, Version 2.0 (the "License");
00006 you may not use this file except in compliance with the License.
00007 You may obtain a copy of the License at
00008 
00009     http://www.apache.org/licenses/LICENSE-2.0
00010 
00011 Unless required by applicable law or agreed to in writing, software
00012 distributed under the License is distributed on an "AS IS" BASIS,
00013 WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 See the License for the specific language governing permissions and
00015 limitations under the License.
00016 
00017 */
00018 
00019 #include "ArduinoMotorShield.hpp"
00020 
00021 #if defined TARGET_KL46Z
00022 
00023 /* This assumes the presence of the cross-wiring on PWM B 
00024    (see "Issues" at http://mbed.org/users/johnb/notebook/mutt-mbed-enabled-robot-vehicle/ )
00025 */
00026 #define MOTOR_A_PWM_PIN     PTA12
00027 #define MOTOR_B_PWM_PIN     PTA5
00028 
00029 #define MOTOR_A_BRAKE_PIN   PTD2
00030 #define MOTOR_B_BRAKE_PIN   PTA13
00031 
00032 #define MOTOR_A_CURRENT_PIN PTB0
00033 #define MOTOR_B_CURRENT_PIN PTB1
00034 
00035 #define MOTOR_A_DIR_PIN     PTD7
00036 #define MOTOR_B_DIR_PIN     PTD5
00037 
00038 #elif defined TARGET_NUCLEO_F401RE 
00039 
00040 #define MOTOR_A_PWM_PIN     PB_3
00041 #define MOTOR_B_PWM_PIN     PB_4
00042 
00043 #define MOTOR_A_BRAKE_PIN   PC_7
00044 #define MOTOR_B_BRAKE_PIN   PA_9
00045 
00046 #define MOTOR_A_CURRENT_PIN PA_0
00047 #define MOTOR_B_CURRENT_PIN PA_1
00048 
00049 #define MOTOR_A_DIR_PIN     PA_6
00050 #define MOTOR_B_DIR_PIN     PA_5
00051 
00052 
00053 #else
00054 
00055 "Error Message: This target's not currently supported!  Please look in ArduinoMotorShield.cpp to add."
00056 
00057 #endif
00058 
00059 ArduinoMotorShield::ArduinoMotorShield() : m_a_motorControl  ( MOTOR_A_PWM_PIN ),     m_b_motorControl  ( MOTOR_B_PWM_PIN ),
00060                                            m_a_brake         ( MOTOR_A_BRAKE_PIN ),   m_b_brake         ( MOTOR_B_BRAKE_PIN ),
00061                                            m_a_motorCurrent  ( MOTOR_A_CURRENT_PIN ), m_b_motorCurrent  ( MOTOR_B_CURRENT_PIN ),
00062                                            m_a_motorDirection( MOTOR_A_DIR_PIN ),     m_b_motorDirection( MOTOR_B_DIR_PIN )
00063 {
00064     m_motorControl[ MOTOR_A ]   = &m_a_motorControl;
00065     m_motorControl[ MOTOR_B ]   = &m_b_motorControl;
00066     m_brake[ MOTOR_A ]          = &m_a_brake;
00067     m_brake[ MOTOR_B ]          = &m_b_brake;
00068     m_motorCurrent[ MOTOR_A ]   = &m_a_motorCurrent;
00069     m_motorCurrent[ MOTOR_B ]   = &m_b_motorCurrent;
00070     m_motorDirection[ MOTOR_A ] = &m_a_motorDirection;
00071     m_motorDirection[ MOTOR_B ] = &m_b_motorDirection;
00072     m_speed[ MOTOR_A ]          = 0;
00073     m_speed[ MOTOR_B ]          = 0;
00074     m_motorForward[ MOTOR_A ]   = 0;
00075     m_motorForward[ MOTOR_B ]   = 0;
00076 }
00077 
00078 void ArduinoMotorShield::SetMotorPower( const Motor_e p_motor, const float p_speed, bool p_force )
00079 {
00080     if( p_force || ( p_speed != m_speed[ p_motor ] ))
00081     {
00082         m_speed[ p_motor ] = p_speed;
00083         
00084         if( m_speed[ p_motor ] > 0.0f )
00085         {
00086             *(m_motorDirection[ p_motor ]) = m_motorForward[ p_motor ];
00087         } else {
00088             *(m_motorDirection[ p_motor ]) = !m_motorForward[ p_motor ];            
00089         }
00090         
00091         (m_motorControl[p_motor])->write( fabs( p_speed ) );        
00092     }
00093 }
00094 
00095 float ArduinoMotorShield::GetMotorCurrent( const Motor_e p_motor )
00096 {
00097     /* AnalogIn returns 0..1.  The feedback from the current monitor is 0V = 0A, vref = MAX */
00098     return( *(m_motorCurrent[ p_motor ]) * MOTOR_MAX_CURRENT );
00099 }
00100 
00101 void ArduinoMotorShield::SetBrake( const Motor_e p_motor, bool p_enable )
00102 {
00103     *(m_brake[ p_motor ]) = p_enable;
00104 }
00105 
00106 void ArduinoMotorShield::SetMotorPolarity( const Motor_e p_motor, const MotorDirection_e p_dir )
00107 {
00108     if( m_motorForward[ p_motor ] != p_dir )
00109     {
00110         m_motorForward[ p_motor ] = p_dir;
00111         /* Reset the motor control to take into account the revised direction */
00112         SetMotorPower( p_motor, m_speed[ p_motor ], true );
00113     }
00114 }