33-2-手推式自動洗地機的設計(全套含CAD圖紙)【含三維SW】
資源目錄里展示的全都有,所見即所得。下載后全都有,請放心下載。原稿可自行編輯修改=【QQ:401339828 或11970985 有疑問可加】
The Cubli: A Cube that can Jump Up and BalanceMohanarajah Gajamohan, Michael Merz, Igor Thommen and Raffaello DAndreaAbstractThis paper introduces the Cubli, a 151515 cmcube that can jump up and balance on a corner. Momentumwheels mounted on three faces of the cube (Fig. 1) rotate at highangular velocities and then brake suddenly, causing the Cubli tojump up. Once the Cubli has almost reached the corner stand-up position, controlled motor torques are applied to make itbalance on its corner. This paper tracks the development of theCublis one dimensional prototype at ETH Zurich and presentspreliminary results.I. INTRODUCTIONInverted pendulum systems have a very rich history 1 andhave been widely used to test, demonstrate and benchmarknew control concepts and theories 2. Furthermore, devel-opment of new control algorithms for the pendulum systemitself is still an active area of research 35.Compared to other 3D inverted pendulum test-beds 8,9 the Cubli has two unique features. One is its relativelysmall footprint, (hence the name Cubli, which is derived fromthe Swiss German diminutive for ”cube”). The other featureis its ability to jump up from a resting position withoutany external support, not only an interesting concept for thecontrol engineer but also also an appealing demonstration forthe general public.Fig. 1.The CAD drawing of the Cubli with covers removedFig. 2 shows the jumping up strategy of the Cubli. Initiallythe Cubli, lying flat on its face, will jump about its edgeby instantaneously stopping one of its momentum wheels.The authors are with the Institute for Dynamic Systems and Control,Swiss Federal Institute of Technology Z urich, Switzerland. The contactauthor is M. Gajamohan, e-mail: gajanethz.chOnce the Cubli is balancing on its edge, the next two wheelsare instantaneously stopped to make it stand on its corner.Finally, an inertial measurement unit (IMU) based stateestimation is performed and the motor torques are preciselycontrolled to make the Cubli continue standing.Whereas a relatively large portion of research tries to avoidimpact or overcome the effects of it 1012, only a smallportion 13, including the Cubli, takes advantage of it. Whilea non-impulsive force is limited by the actuator torque limits,an impact gives forces that are well beyond the actuatorlimitations.4535.3(a)(b)Fig. 2.The Cubli jump-up strategy: (a) Flat to Edge: Initially lying flaton its face, the Cubli jumps up to stand on its edge. (b) Edge to Corner:The Cubli goes from balancing about an edge to balancing on a corner.Once complete, the Cubli will provide an inexpensive,open source test-bed with a relatively small footprint forresearch and education in estimation and control.The three dimensional Cubli design started off with thefollowing question:How to build a 15 cm sided cube that can jumpup and balance on its corner, using off-the-shelfmotors, batteries, and electronic components ?Due to the structures rigidity and off-the-shelf componentconstraint, only the momentum wheels allowed enough de-sign flexibility in terms of mass distribution properties of theCubli. Necessary angular velocities of the momentum wheelsfor jump-up were calculated assuming a perfectly inelasticcollision between the wheels and the pendulum body.Although high angular velocities of the wheels beforebraking can be reduced by increasing the wheel inertia, i.e.,increasing wheel mass since the wheel size is constrained,this was not taken to the extreme since this will result inreduced recovery angles while balancing.A gear chain between the wheel and the motor wasavoided since it would not allow the high angular velocitiesfor jump-up and would add extra weight and volume. Al-though the balancing maneuver, which requires high torques,2012 IEEE/RSJ International Conference onIntelligent Robots and SystemsOctober 7-12, 2012. Vilamoura, Algarve, Portugal978-1-4673-1735-1/12/S31.00 2012 IEEE3722was affected by the choice of no gear, the brushless DCmotors were still able provide enough torque for recoveryangles up to 7.The objective of this paper is to present the concept ofthe three dimensional Cubli along with the development ofthe one dimensional design, modelling, identification, andcontrol. This paper also presents a control procedure toeliminate sensor offsets during the balance maneuver.II. THEONEDIMENSIONALPROTOTYPEFig. 3 illustrates the one dimensional prototype that wasbuilt to examine the feasibility and develop control algo-rithms for the Cubli. Similar momentum exchange wheelbased inverted pendulum designs, except for the brakingmechanism, can be found in 57. The prototype consistsof a square plastic plate that holds the momentum exchangewheel through the motor at its center and the brakingmechanism at one of its corners. The dimension of the plasticplate matches the dimension of the proposed Cubli face, andit will be referred to hereafter as the pendulum body. Theplate is attached to a bearing at the bottom that gives it asingle degree of freedom to pivot around its corner on ahorizontal plane.A. System dynamicsbwllbFig. 3.Illustration of the one dimensional prototype consisting of a squareplastic plate that holds the momentum exchange wheel through the motorat its center. The plate is attached to a bearing at the bottom.Let bdenote the tilt angle of the pendulum body andwrepresent the rotational displacement of the momentumwheel with respect to the pendulum body. The non-lineardynamics of the the setup shown in Fig. 3 is given byb=(mblb+ mwl)g sinb Tm Cbb+ CwwIb+ mwl2,w=?Ib+ Iw+ mwl2?Tm Cww?Iw(Ib+ mwl2)(mblb+ mwl)g sinb Cbb(Ib+ mwl2),(1)where mb, mware the pendulum body and wheel masses,Ibis moment of inertia of the pendulum body around thepivot point, Iwis the moment of inertia of the wheel and themotor rotor around the rotational axis of the motor, l is thedistance between the motor axis and the pivot point, lbis thedistance between the center of mass of the pendulum bodyand the pivot point, g = 9.81 m s2is the gravitationalacceleration, Tmis the torque produced by the motor, andCw, Cbare the dynamic friction coefficients of the pendulumbody and wheel. Since we used a motor that allowed currentset points controlled by an inner loop running at 10 kHz, thecurrent-torque relationship can modelled asTm= Kmu,(2)where, Km= 25.1 103Nm A114 is the torqueconstant of the brushless DC motor used and u is the currentinput.B. Parameter identificationThis subsection describes procedures for identifying theparameters in (1) that cannot be directly measured.lbwas identified by freely hanging the pendulum bodyfrom different corners. To identify Iwand Cw, the momen-tum wheel was driven with different current steps, whilependulum body was rigidly fixed, and the time trace ofwwas recorded. A least squares fit with the measurements toIww(t) = Kmu(t) Cww(t)gave Iwand Cw.To identify Iband Cb, after rigidly fixing the momentumwheel with the pendulum body the whole setup was hungupside down and was made to swing. A least squares fitwith the measurements to(Ib+Iw+mwl2)b(t) = Cbb(t)+(mblb+mwl)g sinb(t)gave Iband Cb. The following table shows all the measuredand identified parameters of the prototype:l0.085 mlb0.075 mmb0.419 kgmw0.204 kgIb3.34 103kg m2Iw0.57 103kg m2Cb1.02 103kg m2 s1Cw0.05 103kg m2 s1C. Braking mechanismFig. 4 shows the current iteration of the braking mecha-nism where an RC servo is used to quickly collide a metalbarrier with the bolt head attached to the momentum wheel.The metal barrier and the RC servo are connected using athin metal sheet to ensure that most of the impact is takenby the metal barrier. Furthermore, the design guarantees thatthe metal barrier is easily replaceable. The RC servo-basedbraking mechanism had several advantages over the initialsolenoid-based braking mechanism in terms of weight (areduction of 39g), power and durability.To test the durability of the stopping mechanism, and toselect the appropriate material for the metal barrier, several3723Fig. 4.The CAD drawing of the RC servo-based braking mechanism: AnRC servo is used to quickly collide a metal barrier (blue) with the bolt head(red) attached to the momentum wheel.jump up trials were done with additional steel plates attachedto the pendulum body such that the mass and the inertiaproperties are equal to the full Cublis face to edge jump asshown in Fig. 8.D. Electronics and softwareThe power, computation and control components were notmounted on the one dimensional prototype to avoid makingthe first prototype too complex. Figure 5 shows the overallelectronics setup except for the power, which was providedby a constant voltage supply.We selected the STM3210E evaluation board, (whichhouses a Cortex-M3 clocked at 72 MHz) from STMicroelec-tronics as the main controller for its rapid prototyping andreadily available community support. The IMU comprised ofa 3-axis accelerometer, ADXL345 from Analog Devices, anda 3-axis rate-gyro using the IDG-500/ISZ-500 series fromInvenSense. The two IMUs, mounted on the pendulum bodyas shown in Fig. 6, was connected to the evaluation boardusing two separate Serial Peripheral Interface (SPI) buses.A 50 W brushless DC motor, EC-45-flat, from MaxonMotor AG was selected to drive the momentum wheels fortheir high energy density as compared to the brushed DCmotors. Embedded hall sensors of the motor were used forwheel speed,w, sensing. The motor was controlled using anoff-the-shelf digital four quadrant motor controller, EPOS250/5, from Maxon. The CANopen protocol was used forthe communication between the motor controller and theevaluation board. Note that for the full Cubli, a miniatureversion of the above controller, DEC module 36/2, will beused.The RC Servo, HSG-5084MG, of the braking mechanismwas driven by the PPM signals from the evaluation board. Fordebugging purposes a high speed rotary magnetic encoder,RE36 15, was used to measure band was connected tothe timing/counter unit of the evaluation board.The STM32 port of the FreeRTOS scheduler was used inthe software framework for its prioritized multitasking func-tionalities provided by a scheduler, and for the small footprintof the binary kernel image (4 kB). A completely open sourceand a free development environment for embedded systemsnamed ODeV 16, based on the Eclipse IDE, was used forthe software development.Remote PCIMU1IMU2EncoderSTM3210ERC ServoUARTPPMCANMaxon motor controllerTIMERSPI2SPI1JTAGCANDevelopment/DebuggingFig. 5.The schematic diagram of the electronics setupIII. ESTIMATION ANDCONTROLA. IMU-based tilt angle estimation and IMU calibrationTo estimate the tilt angle bof the pendulum body, a purelyaccelerometer-based tilt estimation was implemented usingtwo accelerometers. Note that this method can be extended9 to the 3D tilt estimation of the Cubli.Two accelerometers were placed along the diagonal of thependulum body at distances ri, i = 1,2 from the pivot pointas shown in Fig. 6. The two most sensitive measurement axisb exi,b eyiwere placed on the pendulum body plane withb exipointing towards tangential andb eyitowards the radialdirection. With this setup, the measured acceleration of theaccelerometer i, i = 1,2, with respect to the accelerometerframe is given byaim := (rib+ g sinb,ri2b g cosb,0),i = 1,2.The dynamic terms can be eliminated bya1m a2m=(1 )g sinb,(1 )g cosb,0),=:(mx,my,0),where = r1/r2and the estimated tilt angle of thependulum body is given byb:= tan1(mx/my).The mechanical placement errors of the accelerometerswere identified by the following procedure:Record the accelerometer measurements when the pen-dulum body is fixed (b= 0) at various tilt anglesb /4,+/4.Do principle component analysis to find the rotationalplane with respect to the accelerometer frame.Calculate the orientation offset by projecting the mea-surements into the rotational plane and defining a ref-erence frame.3724r1r2b ex2b ey2b ez2b ex1b ey1b ez1bFig. 6.Illustration of the tilt angle estimation setup using two accelerom-eters: Two accelerometers were placed along the diagonal of the pendulumbody at distances ri, i = 1,2 and the ratio between the distances is used toeliminate the dynamic terms, rii, ri2i, i = 1,2 from the measurements.B. Jumping UpAssuming a perfectly inelastic collision i.e., a zero coeffi-cient of restitution, the angular velocity wof the momentumwheel required for jump-up is calculated using: (1) Theconservation of angular momentum during the impactIww= (Iw+ Ib+ mwl2)b,where bis the angular velocity of the pendulum body afterthe impact. (2) The conservation of energy after the impact(b= /4) and until the pendulum body reaches the top(b= 0)12(Iw+ Ib+ mwl2)2b= (mblb+ mwl)g(1 12).Eliminating bfrom both equations gives2w= (2 2)(Iw+ Ib+ mwl2)I2w(mblb+ mwl)g.(3)The uncertainties in the parameters or a non zero coefficientof restitution can make wdeviate from the above calculatedvalue. In this case a simple bisection-based trial and errorlearning procedure can be applied to learn the required w,exploiting the monotic relationship between bachieved afterthe impact and w. The wgiven by (3) can be used as theinitial condition in this case. After the collision, once thependulum body has arrived near the equilibrium position,an LQR based controller, explained in the following section,will start balancing the system.C. Balancing controlLinearizing (1) around (b,b,w) = (0,0,0) gives x(t) = Ax(t) + Bu(t).(4)where x := (b,b,w),A :=010(mblb+mwl)gIb+mwl2CbIb+mwl2CwIb+mwl2(mblb+mwl)gIb+mwl2CbIb+mwl2Cw(Ib+Iw+mwl2)Iw(Ib+mwl2),andB :=0KmIb+mwl2Km(Ib+Iw+mwl2)Iw(Ib+mwl2).A 20 ms sampling time was selected for the digital control,considering the open loop unstable pole of (4) (637.4 ms)and a safety factor of 30. Using this sampling time thecontinuous time system given by (4) was discretized usingzero-order hold and the resulting discrete time model is givenbyxk + 1 = Adxk + Bduk,k N0,(5)where Adand Bdare the discrete-time counterparts of thecontinuous time state matrix A and input matrix B. For thesake of simplicity we use the same notation to represent thecontinuous and discrete time versions of the state x and inputu.Using the above discrete time model, a Linear QuadraticRegulator (LQR) feedback controller of the formuk = Kd(bk,bk,wk)(6)was designed, where Kd= (Kd1,Kd2,Kd3) is the LQRfeedback gain that minimizes the cost functionJ(u) :=Xk=1xTkQxk + uTkRuk,Q 0,R 0,bis the angular velocity estimate of the body from therate gyro, andwis the angular velocity estimate of themomentum wheel from the hall sensors. Fig. 9 illustratesthe balancing performance under (6). As it can be seenfrom the plot, the estimated state of the system convergesto (b,b,w) = (0.058,0.0,37.0). This behavior can beexplained by the following property of the system:(I3 Ad+ BdKd)1Bd=(0,0,KmCw+ Kd3Km),(7)Cw+ Kd3Km6= 0,where I3is the identity matrix of size 3. The physicalinterpretation of this property is that if Ad, Bd, and Kdgivesa stable system, any constant offset in the measurement willresult in a non-zero wheel velocity at steady state. Using thereadings from the absolute encoder attached to the pendulumbody at the pivot point, we localized the offset to the offsetin the tilt angle and redefined the tilt angle estimate asb:= tan1(mx/my) + d = b+ d,d R.To automatically eliminate the above constant tilt angleoffset, the discrete time system given in (5) was extended3725by introducing a low-pass filter with state xfk and thefollowing dynamics:xfk + 1 = (1 )xfk + bk,xf0 = 0,(8)where (0,1) and the controller was modified touk = Kd(bk xfk,bk,wk).(9)The closed loop system given by (5), (8) and (9) is stablewith = 0.02. Now, let (b,b,w) =: x, xf) denote thesteady states of the system, which is the solution to x=Ad x BdKd x BdKd1(d xf) xf=(1 ) xf+ (b+ d).This, with (8), gives x=(I Ad+ BdKd)1BdKd1(d xf)=00KmKd1Cw+Kd3Km(d xf)(10) xf=(1 ) xf+ (b+ d).(11)Finally, (10) and (11) gives (b,b,w, xf) = (0,0,0,d)showing that the system reaches the desired equilibrium stateand the filter state xfconverges to the tilt angle offset d withthe proposed controller. Although the zero mean sensor noiseon the measurements were avoided in the formulation for thesake of simplicity, the results are still valid under this typeof noise.Fig. 10 shows a balancing experiment with the offsetcorrection. The estimated states (b,b,w) converge to(0.058,0,0) and the filter state xfconverges to the offsetvalue 0.058 rad. Fig. 11 shows a balancing experimentwhere the system was externally disturbed at time t = 26s.Furthermore, fig 12 shows the full jump-up and balancingmaneuver starting from rest at b= /4.Fig. 7.A picture of the first one dimensional prototype while balancingFig. 8.The picture shows another one dimensional prototype that wasbuilt with a metal pendulum body with extra masses (on the left side ofthe pendulum body) to test the durability of the braking mechanism. Withall the weights attached, it resembles the full Cublis flat to edge jump, themost critical jump for the Braking mechanism, in terms of mass and inertia.Time swbb05101520253035400510152025303540051015202530355005020100100.100.1Fig. 9.Time traces of the one dimensional prototypes estimatedstates during a balancing run with no offset correction on the body tiltangle. The estimated state of the system converges to (b,b,w) =(0.058,0.0,37.0).IV. CONCLUSION ANDFUTUREWORKThis paper presented the Cubli, a unique 3D invertedpendulum that jumps up using a self-generated impact andbalances using the exchange of angular momentum. The onedimensional prototype has demonstrated various importantaspects of the system, including: the hardware, jump-upusing impact, accelerometer-based tilt estimation, control,and software. The Cubli is currently undergoing its seconditeration with on-board electronics and power. Once success-ful, three copies of the one dimensional prototype will be puttogether to produce the 3D version (See Fig. 1). These resultswill be presented in future work.3726Time swbb05101520253035400510152025303540051015202530355005020100100.100.1Fig. 10.Time traces of the one dimensional prototypes estimated statesduring a balancing run with offset correction on the body tilt angle. The es-timated state of the system converges to (b,b,w) = (0.058,0.0,0.0).Time swbb051015202530350510152025303540051015202530355005020100100.100.1Fig. 11.Time traces of the one dimensional prototypes estimated statesduring a balancing run with offset correction on the body tilt angle and anexternal disturbance at time t = 26 s.Time swbb010203040506070010203040506070010203040506070200204005100.80.60.40.200.2Fig. 12.Time traces of the one dimensional prototypes estimated statesduring a jump-up and balance maneuver.V. ACKNOWLEDGEMENTSThe Authors would like to thank Sebastian Trimpe andRaymond Oung for all the support and discussions sharingtheir experience on building the Balancing Cube 9 andthe Distributed Flight Array 17. Furthermore, the authorswould like to extend their gratitude to Philipp Reist for theidea of the impact based jump-up strategy, Carolina Floresfor the graphics, and Tobias Widmer for helping with theexperiments.REFERENCES1 A. Stephenson, “On a new type of dynamical stability,” Proceedings:Manchester Literary and Philosophical Society, vol. 52, pp. pp. 110,1908.2 P. Reist and R. Tedrake, “Simulation-based lqr-trees with input andstate constraints,” in Robotics and Automation (ICRA), 2010 IEEEInternational Conference on, may 2010, pp. 5504 5510.3 D. Alonso, E. Paolini, and J. Moiola, “Controlling an inverted pendu-lum with bounded controls,” in Dynamics, Bifurcations, and Control,ser. Lecture Notes in Control and Information Sciences.SpringerBerlin / Heidelberg, 2002, vol. 273, pp. 316.4 M. V. Bartuccelli, G. Gentile, and K. V. Georgiou, “On the stability ofthe upside-down pendulum with damping,” Proceedings: Mathemati-cal, Physical and Engineering Sciences, vol. 458, no. 2018, pp. pp.255269, 2002.5 J. Meyer, N. Delson, and R. de Callafon, “Design, modeling andstabilization of a moment exchange based inverted
收藏