小型平臺印刷機(jī)的設(shè)計【印刷機(jī)械-膠印機(jī)設(shè)計】【說明書+CAD+SOLIDWORKS】
小型平臺印刷機(jī)的設(shè)計【印刷機(jī)械-膠印機(jī)設(shè)計】【說明書+CAD+SOLIDWORKS】,印刷機(jī)械-膠印機(jī)設(shè)計,說明書+CAD+SOLIDWORKS,小型平臺印刷機(jī)的設(shè)計【印刷機(jī)械-膠印機(jī)設(shè)計】【說明書+CAD+SOLIDWORKS】,小型,平臺,印刷機(jī),設(shè)計,印刷,機(jī)械,膠印機(jī),說明書,仿單
- 1 - Fast Autonomous Mobile Robot Platform by JC Wolf A report submitted to the University of Plymouth In partial fulfilment for the degree in B Eng (Hons) Robotics and Automated Systems 2003-2004 - 2 - SUMMARY This report gives an introduction to the theory of fast mobile robots and focuses on problems involved and gives different approaches to practical implementation. In order to complete the project, an autonomous mobile robot was designed, built and tested. The designed robot has the approximate dimensions of a wheelchair, to enable it to navigate around buildings. It provides a platform for future development on navigation systems. It has the capabilities to be turned into a complete service robot. Future areas of development have been identified. An obstacle avoidance system has been successfully implemented in order to demonstrate these. Its maximum speed is 1.5 meter per second. An investigated into different areas of research, such as fast sensing techniques for ultra sonic distance measurement, trajectory generation for fast movements and obstacle avoidance, was carried out. Tests have been completed, in order to confirm the trajectory generation theory. The report goes into detail about the circuit design. For the completion of the project a modern micro controller module was designed. Due to the flexibility of the design, the module provided the base for other student projects, as well this one. The power electronics design provides the DC Motors with up to 30 Amperes per channel. This maximum of power for a circuit that does not require expensive specialised components. The project was successfully completed in time. It is part of the final year, in the undergraduate degree course BEng Robotics 2 if(SteeringFeedback 0)SteeringFeedback+=256; / make it look unsigned 3 4 Theta_out = (Theta_in - SteeringFeedback)* STEERING_GAIN)/10; 5 6 / Steering Controller equation 7 Theta_out_old=Theta_out; 8 9 if(Theta_out 0) / is positive PORTB|=0 x02; / relay SDIR (logic 1 , relay pulled) 12 else / is around 0 13 Theta_out=0; / delete error 14 15 16 if(Theta_out 126) Theta_out = 127; / Max Saturation 17 if(Theta_out -126)Theta_out = -127; 18 19 if(Theta_out 0) Theta_out = -Theta_out; / Take absolute value 20 21 22 if(Theta_out = 4) 26 27 28 29 if(SteeringFeedback MIN_ANGLE) 30 if(Theta_out_old MAX_ANGLE) 37 if(Theta_out_old 0) / do not allow to drive the servo more into the limit 38 Theta_out=0; 39 STEERING_PWM=0; 40 else 41 STEERING_PWM=DEADBAND_OFFSET+10; 42 43 else 44 STEERING_PWM=Theta_out; 45 - 35 - 3.3.6 Power Electronics The power electronics drive the motors of the robot and communicate with the notebook through serial. The board also forwards all sensor information to the onboard computer. A photo of the power electonics can be found in the appendix. board features: 3 channel PWM , 4 Quadrant drive max 12 Volt and 30 Ampere per channel current sensing for 2 of the PWM channels A to D converter for servo (8-Bit) 2 quadrature Shaft encoder Inputs (interrupt controlled) - 36 - Fig 25: Left channel of the drive system electronics. - 37 - 3.3.6.1 Circuit inputs 5 and 12 Volt Power LPWM 5 volt square wave from the microcontroller LDIR Direction for the motor RV1 User can set the hardware current limit with the Potentiometer Circuit outputs LM+,LM- Connector for motor LSENSE1/2 Connector for Current Sensing Resistor CLIMIT_LEFT Current limit flag for microcontroller 3.3.6.2 Circuit functionality The PWM signal is level shifted from 5 to 12 Volt through transistor Q10. R16 is a pull-up resistor which comes into action if the pin is virtually disconnected from the microcontroller. There are three possibilities when this can occur: - The microcontroller module has been taken out, but the power is on - The microcontroller is hold on reset during programming - The microcontroller pin is configured as an input The so called “glitch-free” PWM of a Atmel microcontroller can not be interrupted during one PWM cycle. Changing the pin with a “outp()” command will be ignored from the microcontroller. However, for current limiting it is essential to switch off during one cycle, as soon as the current hits the limit. The only way to achieve this, is to configure the pin as an input when the current limit is reached, which will cause the power to cut out, since the pull-up resistor R16 will switch Q10 through. Fast MOS-FET switching: The Q2,Q3,R10 and D6 are responsible for charging and discharging the gate of Q1 as fast as possible. During the switching of Q1 its internal resistance changes from a fraction of a ohm (when switched through) to infinite ohms (when open). Therefore power is dissipated during switching. The slower the switching the more power will be dissipated. Experiments have shown that, without this circuit, at switching frequencies higher than 500 Hz all power will be dissipated for switching. Switching on will cause Q2 to conduct through R10. When switching off the gate discharges through D6 and Q3. - 38 - D2 is the free-wheel diode for the motor. Smoothing capacitors C5 and C7 are placed as close as possible to the MOS-FET. An additional unipolar capacitor with 4700 uF was placed at the power connector of the PCB. Direction control The direction of the motor is changed by applying a signal to Q4, which switches the two automotive relays RL1 and RL2. D3 is a free-wheel diode for the relay coils. 3.3.6.3 Current Limiter design Based upon measurements, the armature resistance is varying with temperature between 0.15 and 0.18 According to the datasheet, the stall current is 85A. AVRVI a 8015.012 =W= (18) Equation 18 confirms the datasheet. Although a Power MOSFET is in series with the motor, in a complete circuit, the maximum continuous current that can occur is still too high for an inexpensive MOSFET. Current limiting is required. Fig 26: current path The circuit on the left hand side, figure 26, describes a model of the motor, MOSFET and current sensing resistor in series. ARRR VI LDSa 48=+= (19) The continuous drain current through a BUZ11 MOSFET, which was chosen for the design, is 30A. Within a PWM cycle the current rises up. And with it the voltage Vsense. Vsense going into a potential divider with low-pass filter, see figure 25, R12,R13, C9. RV1 sets the bias voltage for the transistor and R14 is for safety, so the user can not apply the full 5Volt to the base of the transistor by turning RV1 to 0 . - 39 - Here are the CRO graphs of the signal path in the current sensing circuit. One PWM cycle is shown. Figure 27 Figure 27: This graph represents Vsense, measured directly at the current sensing resistor. Initial switching noise can be seen, as well as the negative inductor voltage at the end of the cycle. The inductor voltage is cut out after the diode responds. Figure 28 Figure 28: Signal at the base of transistor Q9. The low-pass filter removed the switching noise. The signal can be shifted up and down (arrow) with RV1. Figure 29 Figure 29: Showing the output of Q9 going into the micro controller. The transistor inverts the signal. The more the voltage comes near to 0, the higher the current. The graph indicates that the current must be measured more towards the middle of the PWM cycle, in order to get correct reading. The microcontroller is checking the current synchronized with the timer interrupt that also generates the PWM signal. If a 0 is detected (too high current) the software disables the PWM output pin. - 40 - Current limit source code SIG_OVERFLOW1 is the timer that generates the PWM signal as well. SIGNAL(SIG_OVERFLOW1) int i; for(i=0;i22;i+) i+;i-; / initial break if(PINC / Limit not reached , switch off the flag DDRD|=0 x10; else / PC7 is low / Current limit reached DDRD / switch the MOSFET off CurrentLimit|=CLIMITLEFT; / Flag on if(PINC / Limit not reached , switch off the flag DDRD|=0 x20; else / PC6 is low, Current limit reached DDRD / switch the MOSFET off CurrentLimit|=CLIMITRIGHT; / Flag on 3.4 Onboard communication 3.4.1 Serial Communication Speed 38400 baud, 8 data-bits , no parity, one stop-bit The serial protocol used is frame based. Square brackets indicate the start and end of a frame/packet. This is necessary to synchronize the information exchange. It enables the communicating machines to decide when the information is complete and ready to be processed. If synchronization is lost the communications software will wait for the next data start byte “ to regain synchronization. Any data coming in before that will be ignored. The correctness of information transfer within the robot is not critical, since a packet gets out of date within milliseconds. Therefore there is no checksum or protocol extension for acknowledges etc. This protocol is a streaming protocol. If the serial bus would be disconnected and reconnected, everything would continue and re-synchronize automatically. - 41 - Command Explanation LSx Left Motor Speed RSx Right Motor Speed LDC Left Motor Direction Clockwise LDA Left Motor Direction Counter-Clockwise RDC RDA Sx Steering Angle, where x is a signed 8 bit value And 0 degree represents: wheels straight ahead LG RG U Request sensor information x is a 8-bit binary value from 0 to 255 The Sensor data Packet When the Notebook (Master) requests sensor information from the Drive system micro controller, the drive-system microcontroller forwards the request via I2C bus to the sensor systems and collects the data. After that the drive system microcontroller will answer the request with the following packet: n G4 G3 G2 G1 H0 L0 H1 L1 H2 L2 H3 L3 H4 L4 H5 L5 H6 L6 H7 L7 where: n is the number of sensor values being sent / in the system G1 to G4 is the Global time-stamp in order to determine the sampling rate and how old the sample is. Where G4 is the most significant byte (MSB) of the 32-bit unsigned value. Hx and Lx are a 16-bit unsigned value of the sensor, which in this application represent the time-of-flight measured by the ultra-sonic sensors in unit time-stamps. Hx is the MSB. - 42 - 3.4.2 I2C Communication The I2C bus, pronounced “i squared c”, was invented by Philips. It is a fast serial bus with two wires (Clock and Data) plus a ground reference. The AtmelMega 16 has special I2C registers and a interrupt flag. I2C has a protocol stack to manage device addresses and read/write operations. One device acts as a Master, the others are Slaves. Usually the master requests data from the slave. In the current design of the robot, one microcontroller is connected to the onboard PC by RS232 link. In order for the PC to communicate with the other onboard devices such as the ultra sonic sensor microcontroller and the digital compass, the I2C bus is used. The communication protocol used in the robot is described below. The a single byte (Data) is requested from the slave. Master START SLA+W Address RS SLA+R NA STOP Slave A A A Data START is a single bit indicating the start of a frame. SLA+W means, the master is going to transmit a byte onto the bus. A means acknowledge. Address; the Master transmits a slave address. This is used if more than just one slave is on the same bus. RS is a “repeated start”, meaning that the master will continue transmitting SLA+R contains a register number that the master requests. Data is the actual data that the master requested. NA means not acknowledge, which is actually the correct reply of the Master on the end of a frame. STOP ends the transmission like a stop bit on the RS232 bus. The following source code can be installed into the slave. It will generate the correct reply to a master. The slave has an array of registers that can be requested. Each array cell can contain data, such as a ultra sonic distance measurement. volatile unsigned char RegistersREG_MAX; SIGNAL(SIG_2WIRE_SERIAL) static unsigned char reg = REG_MAX; - 43 - switch (TWSR) /* SLAVE RECEIVER */ case TW_SR_SLA_ACK: case TW_SR_ARB_LOST_SLA_ACK: case TW_SR_STOP: case TW_ST_DATA_ACK: case TW_ST_DATA_NACK: TWCR = _BV(TWINT) | _BV(TWEN) | _BV(TWEA) | _BV(TWIE); break; case TW_SR_DATA_ACK: case TW_SR_DATA_NACK: if (reg REG_MAX) Registersreg = TWDR; reg = REG_MAX; else reg = TWDR; TWCR = _BV(TWINT) | _BV(TWEN) | _BV(TWEA) | _BV(TWIE); break; case TW_ST_SLA_ACK: case TW_ST_ARB_LOST_SLA_ACK: if (reg REG_MAX) TWDR = Registersreg; reg = REG_MAX; TWCR = _BV(TWINT) | _BV(TWEN) | _BV(TWIE); break; / Initialize I2C Bus in slave mode void i2c_init(void) DDRC |= 0 x03; / I2C pins for Output PORTC / Output 0 TWSR = 0 x00; TWBR = 28; / I2C Bus Speed,28,18 ? TWAR = 0 xC0; / Our I2C Slave Address TWCR = _BV(TWEN) | _BV(TWEA) | _BV(TWIE); The i2c_init() function must be called once after reset of the micro controller, in order to initialize the micro as a I2C and set the baudrade to 100kHz. - 44 - 4 INTELLIGENT CONTROL 4.1 Kinematic model 4.1.1 Inverse solution for vector based steering The navigation system outputs a velocity vector to the inverse kinematics which calculate the steering angle and wheels speeds. The velocity vector consists of an angle which is relative to the robots current heading angle. The length of the vector is the speed. One can imagine a joystick control for the robot like a remote controlled car has, is the same principle. For example: Joystick more forward is faster; more left is gives smaller turning radius. - 45 - 4.1.2 Inverse Kinematic algorithm wVVV inR += (20) wVVV inL -= (21) 2/)( LR VVV += (22) L VV LR -=w (23) if =0 then r = 20000 meter (seems infinite to an office robot) else wVr = (24) - =-= fififi r mDMF 0 0 (25) if LR VV then -= 90),(2tan xyS FFaq (26) else += 90),(2tan xyS FFaq (27) Fig 30: Steering kinematics Given an velocity vector with the x and y components, corresponding to wV and inV respectively, the output parameters: Steering angle sq and the driving wheel velocities Vr.Vl can be derived. m is defined as the distance between front and rear wheels L is defined as the distance between the two rear wheels r is the radius about a virtual point which the robot is rotating about. n.b. : r L/2 then the point where the robot is rotating about lies within the robot and if r=0 the robot rotates around its origin (on the spot) - 46 - 4.2 Sensors for guidance 4.2.1 Position Fig 31: Position of the ultra sound transducers The reference frame RF is the origin of the robot coordinate system. Is important to arrange the sensors in line with this reference frame. Otherwise the measured distance can not be converted directly into a vector pointing from robot to obstacle. 4.3 Investigation of sensing speed and reaction time Assuming a worst case scenario can determine if the robot can stop or avoid an obstacle in its way. Fig 32: worst case collision scenario Assumptions: Robot and human coming towards each other: sec/300 sec/1 sec/2 mV mV mV Sound H R = -= = 2 measurements are required to determine the humans intentions. The robot has a breaking distance of mdbreaking 5.0= - 47 - Further assumptions are: Robot has a control delay for of 100ms (planning, communications), which is equivalent to a distance of md PLAN 2.0= The difference of the two velocities is the velocity between human and robot: sec/3mVVV HR =-= (28) This simplifies the model to a moving robot with Vr = 3m/sec and a standing human with 0m/sec. Fig 33: model of collision course scenario Time until impact: RR pact V x V dt =D Im (29) Distance until impact x: breakingPLANmm ddddx += 21 (30) Distance Measurement 1 ( 1md ) The ultra sound wave travels x and then reflects on a human and travels back to x - 1md , because the robot moved 1md within the time of measurement. 11 msonicm tVdxx D=-+ (31) Distance the robot travelled during the measurement 11 mRm tVd D= (32) substituted into (31) R m sonicm V dVdx 1 12 =- (33) - 48 - rearranged x V Vd R sonic m 1 2 1 + = (34) Distance Measurement 2 ( 2md ) Distance travelled by the ultrasound is x- 1md towards the obstacle and x-( 2md + 1md ) back to the robot, which travelled 2md during the time of measurement. sonic mm m V dxt 21 2 22 -=D and 22 mRm tVd D= (35) , (36) combined and rearranged 1 1 21 22 + + - = R sonic R sonic m V V V V xd (37) (34) and (37) into (30) breakingPLAN R sonic R sonic R sonic dd V V V V x V Vxx + + - + + = 1 1 21 2 1 12 (38) evaluated with Rv and Vsonic: 96.002.002.01 breakingPLANbreakingPLAN ddddx += - += (39) The equation shows that the measurement time of the ultrasonic sensor is so quick that it can usually be neglected. Control delay and breaking distance are the limiting factors of robots maximum speed. - 49 - 4.4 Navigation and Guidance system modelling The Perception Model also called APM 22 ,see McKerrow P J (1991) is a way of transforming the physical world into a model that the robot can interpret. The Perception Model consist of the following transformation processes 1. MEASUREMENT 2. MODELLING 3. PERCEPTION 4. PLANNING 5. ACTION This model, applied to has been applied to the example guidance System: Sensor data such as Ultrasonic distance and direction is measured and modelled as vectors into the direction the sensor is facing. The robot percepts open space and obstacles by comparing these vectors. The default plan of the robot is to go straight ahead, obstacles cause a change of this plan into a alternative direction. The resultant direction is put into action, which means the robot is following it. 4.4.1 Demo Guidance System In order to show the robot in action a simple guidance program was written. The mission of the robot is to go straight. The vector RobotVelocity determines the directions in which the robot will move. The default mission of the robot is going straight: the vector is set to = 1 0 RobotV . An obstacle on the side (90 degrees) of the robot causes it to correct its course slightly. (Vx=0.15) Obstacles located 30 and 60 degrees sideward call for more avoidance (x=0.32,x=0.55) Obstacles ahead of the robot (Sensor US3 at 0 degrees) - 50 - void Avoidance(void) int i; double Timeout_distance = 1344.0 / 509.0909; / 2.640 meter Vector2D Obstacle7; Vector2D SensorRange7; Vector2D ObstacleSum; Vector2D MissionVector; double isClose = 0.50; / Go Straight RobotVelocity.x = 0.0; RobotVelocity.y = 1.0; if(vabs(Sensor0)(isClose-0.5) / Sensor 0 is located left at 90 RobotVelocity.x = 0.15; RobotVelocity.y = 1.0; else if(vabs(Sensor1)isClose) / Sensor 1 is located left at 60 RobotVelocity.x = 0.32; RobotVelocity.y = 1.0; else if(vabs(Sensor2)isClose) / Sensor 2 is located left at 30 RobotVelocity.x = 0.55; RobotVelocity.y = 1.0; else if(vabs(Sensor4)isClose) / Sensor 4 is located right 30 RobotVelocity.x = -0.55; RobotVelocity.y = 1.0; else if(vabs(Sensor5)isClose) / Sensor 5 is located right 60 RobotVelocity.x = -0.32; RobotVelocity.y = 1.0; else if(vabs(Sensor6)(isClose-0.5) / Sensor 6 is located right 90 RobotVelocity.x = -0.15; RobotVelocity.y = 1.0; / Sensor 3 is located at front if(vabs(Sensor3)0.9)|(vabs(Sensor2)0.6)|(vabs(Sensor4)0.6) RobotVelocity.x = -0.0; RobotVelocity.y = -1.0; if(vabs(Sensor0)isClose)|(vabs(Sensor1)isClose) RobotVelocity.x = 0.40; /go back and right if(vabs(Sensor5)isClose)|(vabs(Sensor6)isClose) RobotVelocity.x = -0.40; /go back and left if(vabs(Sensor1)isClose) see the source for copying conditions. There is NO warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. C:dataatmelsoo-mi Make sure that the version number is = 3.0.0. If the version is e.g. 2.95 then you got the wrong software. Start up PonyProg and check the version by the menu “?” , then “about”. The version number should be 2.05a or higher. - 57 - 2. Get going 2.1 Software Installation 2.1.1 Windows : WinAVR 3.X Just double click the setup. 2.1.2 Linux: gcc 3.x Guide to install avr-gcc 3.3 or 3.4 under Linux No warranty and no support that this will work for every system. But I successfully compiled avr-gcc under Linux with the following packages: avr-libc-1.0.3.tar.bz2 binutils-2.14.tar.bz2 gcc-core-3.4-20040310.tar.bz2 uisp-20040311.tar.bz2 The packages should be compiled in the following order:
收藏