Small Robot Motion Control: The Dilberts

本文详细介绍了作者在两款小型机器人Dilbert和Dilbert II上使用的伺服和运动控制技术。通过采用精确的位置反馈系统,如增量编码器,实现电机速度和位置的精确控制。文章还探讨了PWM信号的不同驱动方式、H桥驱动电路的应用以及PID控制算法的实施。
Encoder Front Page
SRS Home | Front Page | Monthly Issue | Index
Google
Search WWW Search seattlerobotics.org

Small Robot Motion Control: The Dilberts

Larry Barello

larryb@barello.net

This paper describes the servo and motion control techniques used in my robots Dilbert and Dilbert II. Both robots use small DC permanent magnet motors and some sort of encoder scheme that allows the control programs to measure, in absolute terms, how much each motor shaft turns.

Dilbert uses modified Hitec R/C servos as the drive motors. The servos are gutted of all electronics and I only retain the motor and gear train. Dilbert also has a home made encoder system printed directly on the drive wheels with a home made quadrature readout using two Hamamatsu photo reflexive detectors. The Hitec servos are rated at about 1.2 seconds per revolution (RPS) at 4.8 v (standard R/C application). On Dilbert the motors are driven from a 9.6v supply and the motors spin the output shaft at a little over 2 RPS.

Dilbert II uses modified Maxon gear head motors from some surplus thermal printers. The original motors are gears down quite a bit, so I removed two stages of gearing. I also turned a custom axle that is press fit on the output shaft that has a commercial encoder wheel attached. Dilbert II output shaft rotates roughly 12 RPS with a supply voltage of 14.4v

Dilbert has a 4" diameter wheel with 45 encoder stripes for a total of 180 counts per revolution, or, about 1/15" per count. Dilbert II has 2" wheels and a 400-stripe encoder wheel. Due to processing limitations Dilbert II has a total resolution of 800 counts/revolution, or about .00785" per count!

Both Dilbert’s use the L293D, or equivalent, H-Bridge motor driver chip. In both cases the basic PWM rate is ~15 kHz. I use the locked-antiphase drive technique where a 50% PWM rate is Zero motor drive (motor always driven: 50% one way, 50% the other way makes for zero net drive). This works great on Dilbert, but on Dilbert II the Maxon motors have very low inductance so the idle current is roughly ~150 ma – about one 6th the current draw at 100% power. On Dilbert the same idle current level is only ~15 ma. Dilbert II could use a PWM rate of 40-60 kHz, but the micro controller doesn’t support those frequencies.

Servo Feedback Control

A servo is simply a mechanism that slaves some sort of action to some sort of input. A toaster oven is a servo: you set the temperature and the internal mechanism works to keep the oven temperature at the selected value. When talking about mechanical systems, typically some sort of input motion or signal is used to control the output motion of the system using some sort of feedback to maintain the output at a level selected by the input. The accelerator of a car is not a servo system because there is no feedback controlling the speed of a car. The operator provides that. A cruise control, however, is an example of a servo system. The cruise control measures the speed of the car, compares that to the desired velocity and adjusts the accelerometer to keep the speed of the car constant.

To precisely control the position of a motor output shaft some form of absolute position feed back is required. A typical and common method of obtaining precise, absolute shaft position information is via the incremental encoder system.

There are other, less precise, feedback mechanism that can be used to control the output of a motor, but since this paper describes precision, absolute, motion control systems, they will not be discussed.

With the encoder systems attached to the wheels of both Dilbert’s, precision position information is available at all times. There are several things that can be done with the position information.

Velocity Control

A common control mechanism, for small robots, is to control the velocity of a motor. On a typical robot, differential drive is used for steering. In order to go straight both motor shafts have to be turning at precisely the same rate (and the wheels have to be the same diameter as well…). With an encoder one can count how many clicks have gone by in a period and uses that as an indication of velocity. The error between the velocity set point and the actual velocity is used to control the power levels to the motors. In the book "Mobile Robots, from Inspiration to Implementation" there is a very elegant velocity control algorithm that not only controls velocity, but forces both wheels to turn the same amount even if one can’t make it’s velocity set point.

Velocity control often has an integral error term. That is, the algorithm accumulates the error and does further adjustments to the power levels to the motors to correct for and eliminate any velocity error accumulated over time. This might be hard to understand, but imagine if one wheel took just a bit longer to get to speed than the other wheel. During this time the robot would turn ever so slightly toward the slower wheel. Including the integral error term would tend to straighten out the curve over the next small period of time by making the slow wheel go a little faster until the original error was canceled out.

One of the problems with Velocity control is how to measure very low velocities. In order to make the algorithms easy to code, most programs work on a fixed time interval. When the velocity starts to be a low number of counts per interval, the control over the motor power levels gets choppy. Various approaches have been used to counter this: a variable measuring period or measuring the period between counts. Both techniques require much more processing power since many factors, that would reduce to constants with a fixed time period, need to be calculated with each cycle.

Position Control

Position control loops are very much like the traditional R/C servos: you input a desired position and the servo logic drives the output shaft to that position with whatever force is required. Normally one doesn’t think of position control as being appropriate for doing motion control on small robots, but, in fact, it is a very good technique. The trick is to profile a series of positions that the robot is to be in, feeding that string of positions to the servo on a periodic basis. This is called Position Profiling.

With position profiling the forward velocity of the robot can be any arbitrary low amount. It might be that the motor shafts advance only every so often, but they will advance smoothly and the robot will crawl along. With profiling acceleration becomes easy to do as well. Acceleration will be discussed later in this paper.

DC Motors

Small DC motors are easy to model and control. Fortunately for us, they can be reduced to simple terms so our control algorithms are easy to code. The permanent magnet DC motor can be modeled as a device that produces torque proportional to the current flowing through it. It also produced a voltage proportional to the rotational velocity. One last bit of modeling completes the picture: there is a small series resistance in the model. Hence, if one stalls a motor, the current draw and torque produced will be the supply voltage divided by the resistance.

Commonly one reads that the RPM of a motor is proportional to the voltage across it’s terminals – and for most purposes that is true: at any given voltage, the motor will spin up in speed until the generator portion of the motor model matches the supply voltage. At that point no more current will flow into the motor and it will produce zero torque. Of course, there is some amount of friction, so there will be some amount of torque required to spin the motor, thus some amount of current needed. This current causes a voltage drop across the small series resistance in our motor model. This voltage drop takes away from supply voltage and causes the motor to spin a bit slower than the supply voltage would indicate.

In industrial controllers one typically sees a variety of control methods: constant speed, where the applied voltage is "adjusted" for the IR voltage drop across the internal resistance (the controller measures the current though the motor, calculates the voltage drop across the internal resistance and bumps the supply voltage to compensate); Constant torque, which is simply a constant current supply, and the incremental encoder or tachometer feedback systems which, of course, give absolute control over position and speed.

PWM

A typical way to control small DC motors is via PWM, which stands for Pulse Width Modulation. PWM comes in a variety of flavors. The only flavor that I have used has a fixed frequency with a variable on/off cycle. The hardware in Dilbert and Dilbert II has a selectable 8, 9 or 10 bit PWM. The "on" portion of the cycle can be set to any value from 0 to 2^n-1, or, for 8 bit PWM: 0-255. This means that there are 255 steps between 0% and 100% on, during a PWM cycle. As mentioned earlier the Dilbert’s both use locked-antiphase drive, which means that the control range is really –127 to +128. I find that 127 steps of power control are more than adequate for controlling small motors.

H-Bridge

The H-Bridge is the primary means for driving a small DC motor in the forward and reverse directions. A typical small motor driver chip is the L293D or the L298. These are very old designs, but they are cheap and work well. There are lots of newer chips available, but, fundamentally, they all do the same thing: They have a direction input and an enable. By selecting the appropriate directions for the two sides of the H-bridge and enabling the outputs, the computer can control the direction of the motor. By switching the direction and the enable bits the controller can control the direction as well as the amount of power delivered to the motor

There are fundamentally two ways to drive a small motor with a PWM signal: Sign-Magnitude and Locked-antiphase.

Sign-Magnitude

In sign-magnitude the controller sets the direction with the directions bits and then varies the amount of power to the motor with the PWM signal. Typically switching the ENABLE bit of the H-Bridge driver does this. The ratio of ON to OFF determines the amount of power going to the motor.

There is an alternative way to drive the motor: The Enable bit is left ON all the time. One half of the H-Bridge is set forward or backwards and the PWM signal drives the other half of the bridge. The effect of this technique is that the motor is alternatively driven and shorted with the ratio set by the PWM signal

Locked-antiphase

Locked-antiphase is similar to the second version of Sign-Magnitude in that the enable line is always ON. The PWM signal is used to switch both sides of the H-Bridge such that the motor is driven forward or backwards at all times.

Because both forward and reverse are determined by one signal line the amount of control available is only � the apparent PWM control range: Those numbers below 50% duty cycle are reverse and those above are forward.

One of the big advantages to locked-antiphase is that only one line is needed to completely control the H-Bridge motor driver. If you have an I/O constrained MCU, this might be a good option.

Brake vs. Coast

When a DC motor is spinning, it generates a voltage across the terminals, much like a generator. This voltage is a characteristic of the motor and can be found in the specification sheets as something like Volts/RPM. This voltage is also called the Back Electro-Motive Force (EMF). Back EMF can be used to re-charge the power source of the motor control circuit, or, it can be used to brake the spinning of the motor. With an H-Bridge this is accomplished by driving both sides of the H-Bridge the same direction. It is essentially shorting the motor terminals together.

On the L293, and similar devices, the ENABLE bit serves to disconnect the driver from the motor. When this happens, the motor simply spins and generates a voltage. The only time this voltage might be turned into a current is if the back-EMF exceeds the supply voltage and the forward voltage drop of the protection diodes in the H-Bridge driver. When the driver is ENABLED and shorting the motor terminals together, they are not really shorted together: in fact, one is held high, or low, and the other one conducts through the protection diodes in the driver. So, the motor will generate current and brake as long as the back-EMF is greater than one diode + one Vce voltage drop (about 1.1v).

When in brake mode, the motor tends to resist turning. Shorting the terminals together is essentially connecting a very low impedance load to the motor. When a battery is connected to the motor, it too looks like low impedance because, regardless of the current flow or direction, the battery voltage stays the same. The definition of impedance is R = delta V/delta I. Since the delta V stays constant (ideal battery) the resistance (impedance) is zero. The reason the motor only spins up to a certain amount is that the Back-EMF counters the voltage of the battery until there is nothing left to drive current through the motor.

When driving a motor with a PWM signal if one uses Locked-Antiphase, or the second Sign-Magnitude technique, the motor is always connected to a low impedance source (either shorted through the protection diodes, or connected to the supply voltage). The result is that for a given speed the motor will tend to resist speeding up or slowing down for exactly the same reasons that shorting the terminals together cause the motor to be in brake mode.

Driving the motor in Four Quadrants

Locked-Antiphase drives the motor in what is knows as "Four Quadrant Mode". The four quadrants are: Motor accelerating and generating power, Motor accelerating and consuming power, Motor decelerating and generating power and finally, Motor decelerating and consuming power.

In all cases either the motor is consuming electricity and trying to turn a load, or the motor is generating electricity and trying to "hold back" the load.

With Sign-Magnitude with the PWM controlled by the ENABLE line, only the second and fourth quadrants are being utilized. There is no control over the motor in the first and third quadrants. That is when the BRAKE mode comes in handy: for the first quadrant the load is accelerating (think of the robot going down a steep hill) and needs to BRAKE to keep the acceleration to the desired value. The third quadrant is just the opposite: the robot is going up a hill, but you want to slow it down faster than gravity; again, the only way to do this is by BRAKING.

When the motor is always connected to a low impedance source (e.g. locked-antiphase, or the second sign-magnitude configuration) all four quadrants are covered. As soon as the motor enters either the first or third quadrant, the H-Bridge absorbs the generated current and causes the necessary braking action to take place. This is all automatic with no special effort needed on the PWM controller.

Encoder Feedback

All quadrature decoders have at least two signal lines: the A and B lines. An SRS Encoder article has an excellent description of how quadrature signals are generated and decoded. (look about half way down)

Dilbert

In Dilbert the detectors are two photo-reflexive sensors mounted so that they detect the stripes roughly 50% out of phase with each other. That is, roughly � of a stripe after one detector senses the strip, the second sensor will detect it. The resulting signal, from the two detectors, looks like two square waves 90 degrees out of synch with each other. Because Dilbert is relatively slow and has few stripes it is possible to do quadrature decoding by polling the signal lines.  See the photo gallery for Dilbert (Firebot) for images of the encoder.

See Appendix A: Quadrature Decoding State Machine for the source code example.

Dilbert II

In Dilbert II the resolution of the code wheel and the RPM of the wheels makes a polled state machine impossible. In the Atmel 8515 processor there are two external interrupt lines. These lines can be switched, under program control, from rising edge triggered to falling edge triggered. With this control full quadrature encoding can be implemented using interrupts for the A and B lines. However, in Dilbert II, there are two encoders that would require four interrupt lines, so something else has to be done. The decoding in Dilbert II is pseudo quadrature decoding. The A line from each encoder is fed to one of the interrupt lines. Upon either a positive or negative edge the interrupt routine examines the state of the B line to determine if the count is increasing or decreasing.

Pseudo-decoding works with half the resolution of full decoding. Since the positive and negative edge detection flips with each interrupt mechanical jitter on the code wheel will not generate spurious counts.

See Appendix B: Interrupt driven pseudo-quadrature decoding

PID

PID stands for Proportional Integral Derivative. It is a basic filter mechanism used to control some output based upon the aggregate function of factors.  Here are some references for more details: Basics of Proportional-Integral-Derivative Control (3-98) and PID and Servos

PID is actually a differential equation solved in the frequency domain – something way beyond my comprehension and this paper. However, with some assumptions and simplifications the math becomes very simple and lends itself to rational real world explanations.

The major simplification is to perform the algorithm at a fixed time rate. Then, everything having to do with time gets rolled up into the constants. Now the basic formula becomes:

Output = Kp * Proportional error – Kd * Derivative error + Ki * Integral error;

Let’s walk through the formula:

� The proportional term is an output value based upon the difference between the set point and the actual.

� The derivative term is based upon the first derivative of the proportional error, or, the velocity of the error. I.e. is the error getting smaller or larger as time goes by.

� The integral term is the opposite of the derivative term: it is the sum of all errors over time. The integral term is included to allow the controller to advance the output such that all errors are eventually canceled out.

The constants, Kp, Kd and Ki are just factors, or gain values used to mix the various terms together to get the resulting equation. These factors will change based upon the quality of the motors, the weight of the robot and the charge of the batteries driving the motors. With enough information and proper specifications for your components it is possible to actually compute the exact values for the various gains. In practice, for hobby robotics, we just use trial and error to get good enough values.

In a practical implementation of the PID algorithm, if one is using integer math, is to scale the terms (e.g. multiply by a factor) and divide the output by that factor. In this way fractional values can be used. In the Dilbert’s, the output factor Ko is used:

return (Output/Ko);

Tuning PID controllers

See the following references for more information on PID and tuning: Adjusting PID Gains

A quick and dirty way to tune is as follows:

Set Kd and Ki to zero and Ko to 1.

Increase Kp and move the robot with an impulse function (fancy way of saying, force it forward a bit and let go). If the robot races away, then you have the sign of your P term inverted: either swap the connection to the motor, or, use a negative number for Kp.

Increase Kp until the robot starts to oscillate, that is, it doesn’t just move towards the set point, but wiggles back and forth around it. The oscillations should die down quickly or you have Kp way too high. Some references suggest 60% of the value that causes strong oscillations is a good place to start.

Now, start increasing Kd. At some point Kd should cause the wriggling to stop and the robot should just snap towards the set point and come to a smooth halt when it reaches it. Kd is a velocity term and it comes to dominate the output function when the robot is near to it’s goal. Since it is subtracted (see above) it causes the power to be decreased, and, even reversed to halt the robot at just the right spot.

If Kd is too big, really bad oscillations will occur. Drop it back. You can fiddle with Kp and Kd to see just how snappy you can make your robot. In any case, if either is too large the robot will oscillate around its set point.

Ki is harder: if absolute position is you goal, you will need Ki. Ki is often the inverse of Kd. If Kd is 10, then you might expect Ki to be 1/10. This is where Ko comes into play. You will need to multiply Kp and Kd by some factor (say, 8) and set Ko to 8, that won’t change a thing. Then you can start to increase Ki to see what effect it has on the stability of your robot.

Basic Motion Control

Basic motion control couldn’t be simpler. In Dilbert II the motor control structure contains several elements for motion control: VelocitySetpoint, Velocity and Acceleration. All numbers are maintained as 8.8 signed binary numbers. It is the fractional numbers that give Dilbert so much control: Velocities can be as low as 1/256 of an encoder count/loop to as high as 127counts per loop. Fractional velocities work very well too: as the fractional part accumulates and rolls over, the encoder set point bumps up by one. This "extra" count happens on a periodic basis depending upon the fractional amount and results in a smooth motion at the desired velocity.

Please refer to Appendix D, basic motion control, for the code details.

The motion control code is called from the PID loop code at the PID loop rate. With each cycle the position set point is modified by the Velocity amount. The Acceleration value is used to ramp Velocity from where ever it is to the new VelocitySetpoint value.

To start motion the code simply has to write into the Motor Control Structure the desired velocity and the Motor Control task takes over. E.g.

Left->VelocitySetpoint = Right->VelocitySetpoint = 0x0A00;

In the above example, the velocity is 0A.00 hex, or 10.00. That means the robot will move forward ten encoder counts per control loop – assuming the motors can propel the robot forward that fast.

Acceleration must be set as well. On the Dilbert’s, acceleration is fixed and initialized during boot time at 0x0070. I picked a value that works well over the range of battery voltages I can expect, and how good the wheels are at gripping the floor. Since the acceleration is less than 1 (e.g. 00.70 hex) it takes two cycles before the robot even begins to move. The first cycle sets Velocity to 00.70; the second to 00.E0; the third to 01.50 and so on.

With a velocity of 10 and an acceleration of 0x00.70 it takes 22 cycles to ramp up to the VelocitySetpoint. Over those 22 cycles the robot moves the sum of (1 + 2 + 3 + … + 22) acceleration units, which comes out to 253 * 0x70 or 0x6E.B0. Since we are only concerned with the whole part, the robot moves 0x6E encoder counts before hitting the VelocitySetpoint. This number is important if Dilbert II is traveling with no particular end point in mind since he will travel that many encoder clicks beyond the point that the control program sets the velocity to zero. So, the control code needs to anticipate stopping and initiate stopping 0x6E counts early when traveling at a velocity of 10.

Most robotic contests have speed, as one of the objectives, so there is no reason, for the most part, to accelerate any slower than necessary. However there are times when it is necessary to alter the acceleration. For example when the robot’s path must describe an arc. This should be simple enough, yes? Just set the velocity of one wheel higher than the other and away it goes. Well, with acceleration that doesn’t work: the slower wheel will reach its velocity set point sooner than the faster wheel. What actually happens is that the robot goes "straight", both wheels accelerating in synch, until the slower wheel hits its set point, then the robot will starts to turn.

The solution is to modify the acceleration value as well: if wheel A turns � the speed of wheel B (to get the arc you want), then the acceleration on wheel A should be � that of wheel B.

How to travel a particular distance

It is easy to predict when motion will hit the set point velocity or reach zero. That is just the VelocitySetpoint/acceleration. What is harder is predicting when to set the velocity to zero in order to stop on a pre-determined point. The math is a little complicated because you need to integrate the acceleration and set the velocity set point back to zero the integrated amount before the desired stopping point. This is exactly what I did in the previous section in calculating the overshoot for a velocity of 10 with an acceleration of 0x70.

The math becomes simple for line segments of a fixed distance where the set point velocity is reached. All you need to do is set the velocity and wait for "distance/velocity" number of control cycles before setting the velocity to zero. Note: motion does not stop when the velocity set point is set to zero. It takes "velocity/acceleration" number of cycles for motion to stop.

What happens is that while the robot has not moved the anticipated amount during the time interval, it makes up the difference while decelerating back to zero.

How to turn a particular amount

Turning is pretty much the same as moving in a straight line. For a given velocity and acceleration you can calculate the precise number of cycles to rotate the desired amount. With spinning it is very easy since each wheel does the same thing, but inverted relative to each other. For Arcs it is a little different since you need to figure out the differential velocity and acceleration for each wheel. However, once that is done, the number of cycles can be calculated for just one side, the other will follow along in sync.

Appendixes

The following code examples are for the Atmel AVR microprocessors. The assembly code is for the IAR assembler and the C code is for the GCC-AVR compiler.  You can find the gcc-avr compiler and tool chain here: Atmel for Dummies

RTOS system calls are for AvrX, a small RTOS that I wrote for my own robotics work. 

The following is the data structure used by the motor control and motion routines. The PWM output is eight bits and is initialized elsewhere (code not illustrated).

typedef struct

{

    long Setpoint; // 24.8 number

    long Encoder; // Current position

    int8_t Kp;

    int8_t Kd;

    int8_t Td;

    int8_t Ki;

    int8_t Ko; // Output Scale

    int16_t PrevErr;

    int16_t Ierror;

    int16_t Velocity;

    int16_t VelocitySetpoint;

    int16_t Acceleration;

} MotorInfo, * pMotorInfo;

#define MAXOUTPUT 0x7F

 

Appendix A: Quadrature Decoding State Machine

This code is from Dilbert which has a slightly different motor control structure and names.  Due to the slow nature of Dilbet's encoders (maximum of 360 state changes a second), the code loads, increments or decrements the encoder value and stores it back into the motor control structure.

;+

; Left/RightEncoderInterrupt

;

; Called from PWM overflow interrupt. Does quadrature decoding of our

; encoder inputs. This gives us 4x resolution on our 45 segment encoder

; wheels (total counts/revolution = 180)

;

; There are a bunch of invalid state changes (state0 -> state2 for example)

; and this code completely ignores those possibilities. If the rate of

; change is lower than the polling rate of this code, then there can't

; be any invalid state changes.

;-

A = 1<<0         ; Encoder A Line

B = 1<<1         ; Encoder B line

STATE0 = 0       ; Increment if 0->1, 1->2, 2->3 or 3->0

STATE1 = B       ; Decrement if 0->3, 3->2, 2->1 or 1->0

STATE2 = A + B

STATE3 = A

 

ProcessEncoder:

    clr Xh

    sbic SWITCH, Right_Enc_A

    sbr Xh, A

    sbic SWITCH, Right_Enc_B

    sbr Xh, B

    ldi Zl, low(RightMotor)

    ldi Zh, high(RightMotor)

    rcall DecodeState

 

    clr Xh

    sbic SWITCH, Left_Enc_A

    sbr Xh, A

    sbic SWITCH, Left_Enc_B

    sbr Xh, B

    ldi Zl, low(LeftMotor)

    ldi Zh, high(LeftMotor)

DecodeState:

    ldd Xl, Z+PreviousState

    ldd Yl, Z+Encoder+1

    ldd Yh, Z+Encoder

    cp Xh, Xl

    breq DecodeExit

State0:

    cpi Xl, STATE0

    brne State1

 

    cpi Xh, STATE1

    breq Increment

    cpi Xh, STATE3

    breq Decrement

    rjmp DecodeExit

State1:

    cpi Xl, STATE1

    brne State2

    cpi Xh, STATE2

    breq Increment

    cpi Xh, STATE0

    breq Decrement

    rjmp DecodeExit

State2:

    cpi Xl, STATE2

    brne State3

 

    cpi Xh, STATE3

    breq Increment

    cpi Xh, STATE1

    breq Decrement

    rjmp DecodeExit

State3:

    cpi Xh, STATE0

    breq Increment

    cpi Xh, STATE2

    brne DecodeExit

Decrement:

    sbiw Yl, 2     ; Save a word and a cycle by falling

Increment:         ; through

    adiw Yl, 1

DecodeExit:

    std Z+PreviousState, Xh

    std Z+Encoder+1, Yl

    std Z+Encoder, Yh

    ret

 

 

Appendix B: Pseudo-Quadrature decoding

This is code from Dilbert II which has a slightly different hardware configuration that Dilbert.  The assember used, below, is GAS, or Gnu Assembler, so the directives are slightly different than those in Dilbert.  The interrupt rate (state change rate) can be as high as 12000/second, so I reserve memory for the left and right incremental encoder count and clear that out periodically in the main motor control task.  Atmel assembler (and GAS) doesn't have an op-code for add immediate, so, I use the subtract immediate (subi) with a negative number when adding.  One last note: this is code for just the right side encoder.

;+
; INT0_Interrupt
;
; Fields the A line for an encoder. Increments/Decrements a
; register counter per the state of the B line. Flips sense of 
; external interrupt in preparation for the next state transition.
;
; Because we dont interrupt on the B line, this only does 
; 1/2 quadurature decoding.
;
; ~40 cycles/interrupt (including call and return)
;-
    .func _interrupt0_
    .global _interrupt0_
_interrupt0_:
    push R31
    push R30
    push R29
    in R31, SREG
    in R30, MCUCR
    lds R29, RightEncoder

    sbrc R30, ISC00 ; Was this an up or down event?
    rjmp INT0_up

    subi r29, lo8(-1)
    sbis Right_Enc_B
    subi R29, 2

    sbr R30, 1<<ISC00 ; Switch Trigger to rising edge
    rjmp INT0_done
INT0_up:
    subi R29, 1
    sbis Right_Enc_B
    subi r29, lo8(-2)

    cbr R30, 1<<ISC00 ; Switch Trigger to falling edge
INT0_done:
    sts RightEncoder, R29
CommonExit:
    out MCUCR, R30 
    out SREG, R31
    pop R29
    pop R30
    pop R31
    reti
.endfunc

Appendix C: Pid Algorithm

The following C code illustrates just how sparse the PID algorithm can be. Implicit in all this is the periodic sampling rate, or Td. For Dilbert II Td is 10ms or 100hz. 

int DoPid(MotorInfo *p)

{

    int Perror, output;

 

    // Set point is an 24.8 number (+/- 1 mile@ 130/inch)

 

    Perror = (p->Setpoint>>8) - p->Encoder;

 

    // Derivative error is the delta Perror over Td

 

    output = (p->Kp*Perror + p->Kd*(Perror - p->PrevErr) + p->Ki*p->Ierror)/p->Ko;

    p->PrevErr = Perror;

 

    // Accumulate Integral error *or* Limit output.

    // Stop accumulating when output saturates

    

    if (output >= MAXOUTPUT)

        output = MAXOUTPUT;

    else if (output <= -MAXOUTPUT)

        output = -MAXOUTPUT;

    else

        p->Ierror += Perror;

    

    // Convert output to 0xFF-0x7F-0x00 (Fwd, neutral, Rev)

    // Locked anti-phase drive.

    

    return (output - (MAXOUTPUT+1));

}

 

 

Appendix D: Motion Control

The motion control is very simple.  Adding an incremental position to the position set point on a periodic basis essentially sets the velocity.  In the following code I broke out the "AddToPosition" so that Dilbert's wall following and line following code could "adjust" the relative wheel positions

 

/*+ ---------------------------------------------------------

    void DoMotion(MotorInfo *p)

    Called at the loop rate to add "velocity" to the set point thus

    effecting a motion.

    Velocity is ramped up and down by "acceleration"

    Velocity and Acceleration are 8.8 numbers. Velocity

    is added to the setpoint (an 24.8 number)

-*/

void DoMotion(MotorInfo *p)

{

    if (p->Velocity < p->VelocitySetpoint)

    {

        p->Velocity += p->Acceleration;

        if (p->Velocity > p->VelocitySetpoint)

            p->Velocity = p->VelocitySetpoint;

    }

    else

    {

        p->Velocity -= p->Acceleration;

        if (p->Velocity < p->VelocitySetpoint)

            p->Velocity = p->VelocitySetpoint;

    }

    AddToPosition(p, p->Velocity);

}

/*+ -------------------------------------------------------------

    void AddToPosition(pMotorInfo, int)

    Add an 8.8 value to the current setpoint.

          Do this with interrupts off since the motor control

    task might be reading the long value (e.g. four bytes)

-*/

void AddToPosition(pMotorInfo p, int16_t o)

{

    char s = inp(SREG);

    cli();

    p->Setpoint += o; // Set point is 24.8 number

    outp(s, SREG); // Restore interrupt status

}

 

 

Appendix E: Top Level Motor Control

The following code illustrates the actual working Motor Control task using AvrX, the authors RTOS. This same code could be called as an ISR or Interrupt Service Routine with few modifications.

AVRX_TASKDEF() is a macro that takes the entry point, extra stack space needed and priority as the three arguments and builds the required data structures for C.  I set pointers to the motor control structures because the GNU compiler actually produces better code through pointers than direct references to structure members (e.g. 'p->Encoder =' produces better code than 'Left.Encoder =').

extern MotorInfo Left, Right;

AVRX_TASKDEF(MotorTask, 28, 2)

{

    pMotorInfo pLeft=&Left, pRight=&Right;

    int8_t LeftEnc, RightEnc;

    extern int8_t RightEncoder, LeftEncoder;

    MotorInit();

    while(1)

    {

        AvrXStartTimer(&MotorTimer, MILLISECOND(10));

        AvrXSetSemaphore(&MotorLoop); // Synchronize other motion tasks

 

        BeginCritical();                // Read encoders

        LeftEnc = LeftEncoder;

        LeftEncoder = 0;

        RightEnc = RightEncoder;

        RightEncoder = 0;

        EndCritical();

        pLeft->Encoder += LeftEnc;      // Update motor structures

        pRight->Encoder += RightEnc;

        DoMotion(pLeft);                // Do motion control

        outp(DoPid(pLeft), LEFT_DRIVEL);// Do PID and output power level

        DoMotion(pRight);

        outp(DoPid(pRight), RIGHT_DRIVEL);

        AvrXWaitTimer(&MotorTimer);     // Wait for timer to expire

    }

}

 

 

ros2中晃动imu,但是我的机器人模型不跟着晃动,而且里程计一开,里程计跑走,但是imu和机器人模型还在原地,以下是我的各个文件代码,情分析一下为什么:wheeltec_robot.cpp文件代码为: #include "turn_on_wheeltec_robot/wheeltec_robot.h" #include "turn_on_wheeltec_robot/Quaternion_Solution.h" #include "wheeltec_robot_msg/msg/data.hpp" sensor_msgs::msg::Imu Mpu6050;//Instantiate an IMU object //实例化IMU对象 using std::placeholders::_1; using namespace std; rclcpp::Node::SharedPtr node_handle = nullptr; //自动回充使用相关变量 bool check_AutoCharge_data = false; bool charge_set_state = false; /************************************** Date: January 28, 2021 Function: The main function, ROS initialization, creates the Robot_control object through the Turn_on_robot class and automatically calls the constructor initialization 功能: 主函数,ROS初始化,通过turn_on_robot类创建Robot_control对象并自动调用构造函数初始化 ***************************************/ int main(int argc, char** argv) { rclcpp::init(argc, argv); //ROS initializes and sets the node name //ROS初始化 并设置节点名称 turn_on_robot Robot_Control;//Instantiate an object //实例化一个对象 Robot_Control.Control();//Loop through data collection and publish the topic //循环执行数据采集和发布话题等操作 return 0; } /************************************** Date: January 28, 2021 Function: Data conversion function 功能: 数据转换函数 ***************************************/ short turn_on_robot::IMU_Trans(uint8_t Data_High,uint8_t Data_Low) { short transition_16; transition_16 = 0; transition_16 |= Data_High<<8; transition_16 |= Data_Low; return transition_16; } float turn_on_robot::Odom_Trans(uint8_t Data_High,uint8_t Data_Low) { float data_return; short transition_16; transition_16 = 0; transition_16 |= Data_High<<8; //Get the high 8 bits of data //获取数据的高8位 transition_16 |= Data_Low; //Get the lowest 8 bits of data //获取数据的低8位 data_return = (transition_16 / 1000)+(transition_16 % 1000)*0.001; // The speed unit is changed from mm/s to m/s //速度单位从mm/s转换为m/s return data_return; } /************************************** Date: January 28, 2021 Function: The speed topic subscription Callback function, according to the subscribed instructions through the serial port command control of the lower computer 功能: 速度话题订阅回调函数Callback,根据订阅的指令通过串口发指令控制下位机 ***************************************/ void turn_on_robot::Cmd_Vel_Callback(const geometry_msgs::msg::Twist::SharedPtr twist_aux) { short transition; //intermediate variable //中间变量 Send_Data.tx[0]= 0x06; //frame head 0x7B //帧头0X7B //Send_Data.tx[1] = AutoRecharge; //set aside //预留位 Send_Data.tx[1] = FRAME_HEADER; Send_Data.tx[2] = 0; //set aside //预留位 //The target velocity of the X-axis of the robot //机器人x轴的目标线速度 transition=0; transition = twist_aux->linear.x*1000; //将浮点数放大一千倍,简化传输 (mm/s) Send_Data.tx[4] = transition; //取数据的低8位 Send_Data.tx[3] = transition>>8; //取数据的高8位 //The target velocity of the Y-axis of the robot //机器人y轴的目标线速度 transition=0; transition = twist_aux->linear.y*1000; Send_Data.tx[6] = transition; Send_Data.tx[5] = transition>>8; //The target angular velocity of the robot's Z axis //机器人z轴的目标角速度 transition=0; transition = twist_aux->angular.z*1000; //(1000*rad/s) Send_Data.tx[8] = transition; Send_Data.tx[7] = transition>>8; Send_Data.tx[9]=Check_Sum(9,SEND_DATA_CHECK); //For the BCC check bits, see the Check_Sum function //BCC校验位,规则参见Check_Sum函数 Send_Data.tx[10]=0x0d; //frame tail 0x7D //帧尾0X7D Send_Data.tx[11]=0x0a; try { Stm32_Serial.write(Send_Data.tx,sizeof (Send_Data.tx)); //Sends data to the downloader via serial port //通过串口向下位机发送数据 } catch (serial::IOException& e) { RCLCPP_ERROR(this->get_logger(),("Unable to send data through serial port")); //If sending data fails, an error message is printed //如果发送数据失败,打印错误信息 } } /************************************** Date: January 28, 2021 Function: Publish the IMU data topic 功能: 发布IMU数据话题 ***************************************/ void turn_on_robot::Publish_ImuSensor() { sensor_msgs::msg::Imu Imu_Data_Pub; //Instantiate IMU topic data //实例化IMU话题数据 Imu_Data_Pub.header.stamp = rclcpp::Node::now(); Imu_Data_Pub.header.frame_id = gyro_frame_id; //IMU corresponds to TF coordinates, which is required to use the robot_pose_ekf feature pack //IMU对应TF坐标,使用robot_pose_ekf功能包需要设置此项 Imu_Data_Pub.orientation.x = Mpu6050.orientation.x; //A quaternion represents a three-axis attitude //四元数表达三轴姿态 Imu_Data_Pub.orientation.y = Mpu6050.orientation.y; Imu_Data_Pub.orientation.z = Mpu6050.orientation.z; Imu_Data_Pub.orientation.w = Mpu6050.orientation.w; Imu_Data_Pub.orientation_covariance[0] = 1e6; //Three-axis attitude covariance matrix //三轴姿态协方差矩阵 Imu_Data_Pub.orientation_covariance[4] = 1e6; Imu_Data_Pub.orientation_covariance[8] = 1e-6; Imu_Data_Pub.angular_velocity.x = Mpu6050.angular_velocity.x; //Triaxial angular velocity //三轴角速度 Imu_Data_Pub.angular_velocity.y = Mpu6050.angular_velocity.y; Imu_Data_Pub.angular_velocity.z = Mpu6050.angular_velocity.z; Imu_Data_Pub.angular_velocity_covariance[0] = 1e6; //Triaxial angular velocity covariance matrix //三轴角速度协方差矩阵 Imu_Data_Pub.angular_velocity_covariance[4] = 1e6; Imu_Data_Pub.angular_velocity_covariance[8] = 1e-6; Imu_Data_Pub.linear_acceleration.x = Mpu6050.linear_acceleration.x; //Triaxial acceleration //三轴线性加速度 Imu_Data_Pub.linear_acceleration.y = Mpu6050.linear_acceleration.y; Imu_Data_Pub.linear_acceleration.z = Mpu6050.linear_acceleration.z; imu_publisher->publish(Imu_Data_Pub); //Pub IMU topic //发布IMU话题 } /************************************** Date: January 28, 2021 Function: Publish the odometer topic, Contains position, attitude, triaxial velocity, angular velocity about triaxial, TF parent-child coordinates, and covariance matrix 功能: 发布里程计话题,包含位置、姿态、三轴速度、绕三轴角速度、TF父子坐标、协方差矩阵 ***************************************/ void turn_on_robot::Publish_Odom() { //Convert the Z-axis rotation Angle into a quaternion for expression //把Z轴转角转换为四元数进行表达 tf2::Quaternion q; q.setRPY(0,0,Mpu6050_Data.imu_yaw); geometry_msgs::msg::Quaternion odom_quat=tf2::toMsg(q); nav_msgs::msg::Odometry odom; //Instance the odometer topic data //实例化里程计话题数据 odom.header.stamp = rclcpp::Node::now(); ; odom.header.frame_id = odom_frame_id; // Odometer TF parent coordinates //里程计TF父坐标 odom.pose.pose.position.x = Robot_Pos.X; //Position //位置 odom.pose.pose.position.y = Robot_Pos.Y; //odom.pose.pose.position.z = Robot_Pos.Z; odom.pose.pose.orientation = odom_quat; //Posture, Quaternion converted by Z-axis rotation //姿态,通过Z轴转角转换的四元数 odom.child_frame_id = robot_frame_id; // Odometer TF subcoordinates //里程计TF子坐标 odom.twist.twist.linear.x = Robot_Vel.X; //Speed in the X direction //X方向速度 //odom.twist.twist.linear.y = Robot_Vel.Y; //Speed in the Y direction //Y方向速度 odom.twist.twist.angular.z = Mpu6050.angular_velocity.z; //Angular velocity around the Z axis //绕Z轴角速度 //There are two types of this matrix, which are used when the robot is at rest and when it is moving.Extended Kalman Filtering officially provides 2 matrices for the robot_pose_ekf feature pack //这个矩阵有两种,分别在机器人静止和运动的时候使用。扩展卡尔曼滤波官方提供的2个矩阵,用于robot_pose_ekf功能包 //if(Robot_Vel.X== 0&&Robot_Vel.Y== 0&&Robot_Vel.Z== 0) if(Robot_Vel.X== 0) //If the velocity is zero, it means that the error of the encoder will be relatively small, and the data of the encoder will be considered more reliable //如果velocity是零,说明编码器的误差会比较小,认为编码器数据更可靠 memcpy(&odom.pose.covariance, odom_pose_covariance2, sizeof(odom_pose_covariance2)), memcpy(&odom.twist.covariance, odom_twist_covariance2, sizeof(odom_twist_covariance2)); else //If the velocity of the trolley is non-zero, considering the sliding error that may be brought by the encoder in motion, the data of IMU is considered to be more reliable //如果小车velocity非零,考虑到运动中编码器可能带来的滑动误差,认为imu的数据更可靠 memcpy(&odom.pose.covariance, odom_pose_covariance, sizeof(odom_pose_covariance)), memcpy(&odom.twist.covariance, odom_twist_covariance, sizeof(odom_twist_covariance)); odom_publisher->publish(odom); //Pub odometer topic //发布里程计话题 } /************************************** Date: January 28, 2021 Function: Publish voltage-related information 功能: 发布电压相关信息 ***************************************/ void turn_on_robot::Publish_Voltage() { std_msgs::msg::Float32 voltage_msgs; //Define the data type of the power supply voltage publishing topic //定义电源电压发布话题的数据类型 static float Count_Voltage_Pub=0; if(Count_Voltage_Pub++>10) { Count_Voltage_Pub=0; voltage_msgs.data = Power_voltage; //The power supply voltage is obtained //电源供电的电压获取 voltage_publisher->publish(voltage_msgs); //Post the power supply voltage topic unit: V, volt //发布电源电压话题单位:V、伏特 } } ////////// 回充发布与回调 //////// /************************************** Date: January 17, 2022 Function: Pub the topic whether the robot finds the infrared signal (charging station) 功能: 发布机器人是否寻找到红外信号(充电桩)的话题 ***************************************/ void turn_on_robot::Publish_RED() { std_msgs::msg::UInt8 msg; msg.data=Red; RED_publisher->publish(msg); } /************************************** Date: January 14, 2022 Function: Publish a topic about whether the robot is charging 功能: 发布机器人是否在充电的话题 ***************************************/ void turn_on_robot::Publish_Charging() { static bool last_charging; std_msgs::msg::Bool msg; msg.data=Charging; Charging_publisher->publish(msg); if(last_charging==false && Charging==true)cout<<GREEN<<"Robot is charging."<<endl<<RESET; if(last_charging==true && Charging==false)cout<<RED <<"Robot charging has disconnected."<<endl<<RESET; last_charging=Charging; } /************************************** Date: January 28, 2021 Function: Publish charging current information 功能: 发布充电电流信息 ***************************************/ void turn_on_robot::Publish_ChargingCurrent() { std_msgs::msg::Float32 msg; msg.data=Charging_Current; Charging_current_publisher->publish(msg); } /************************************** Date: March 1, 2022 Function: Infrared connection speed topic subscription Callback function, according to the subscription command through the serial port to set the infrared connection speed 功能: 红外对接速度话题订阅回调函数Callback,根据订阅的指令通过串口发指令设置红外对接速度 ***************************************/ void turn_on_robot::Red_Vel_Callback(const geometry_msgs::msg::Twist::SharedPtr twist_aux) { short transition; //intermediate variable //中间变量 Send_Data.tx[0]=FRAME_HEADER; //frame head 0x7B //帧头0X7B Send_Data.tx[1] = 3; //Infrared docking speed setting flag bit = 3 //红外对接速度设置标志位=3 Send_Data.tx[2] = 0; //set aside //预留位 //The target velocity of the X-axis of the robot //机器人x轴的目标线速度 transition=0; transition = twist_aux->linear.x*1000; //将浮点数放大一千倍,简化传输 Send_Data.tx[4] = transition; //取数据的低8位 Send_Data.tx[3] = transition>>8; //取数据的高8位 //The target velocity of the Y-axis of the robot //机器人y轴的目标线速度 transition=0; transition = twist_aux->linear.y*1000; Send_Data.tx[6] = transition; Send_Data.tx[5] = transition>>8; //The target angular velocity of the robot's Z axis //机器人z轴的目标角速度 transition=0; transition = twist_aux->angular.z*1000; Send_Data.tx[8] = transition; Send_Data.tx[7] = transition>>8; Send_Data.tx[9]=Check_Sum(9,SEND_DATA_CHECK); //BCC check //BCC校验 Send_Data.tx[10]=FRAME_TAIL; //frame tail 0x7D //帧尾0X7D try { Stm32_Serial.write(Send_Data.tx,sizeof (Send_Data.tx)); //Sends data to the downloader via serial port //通过串口向下位机发送数据 } catch (serial::IOException& e) { RCLCPP_ERROR(this->get_logger(),("Unable to send data through serial port")); //If sending data fails, an error message is printed //如果发送数据失败,打印错误信息 } } /************************************** Date: January 14, 2022 Function: Subscription robot recharge flag bit topic, used to tell the lower machine speed command is normal command or recharge command 功能: 订阅机器人是否回充标志位话题,用于告诉下位机速度命令是正常命令还是回充命令 ***************************************/ void turn_on_robot::Recharge_Flag_Callback(const std_msgs::msg::Int8::SharedPtr Recharge_Flag) { AutoRecharge=Recharge_Flag->data; } //服务 void turn_on_robot::Set_Charge_Callback(const shared_ptr<turtlesim::srv::Spawn::Request> req,shared_ptr<turtlesim::srv::Spawn::Response> res) { Send_Data.tx[0]=FRAME_HEADER; //frame head 0x7B //֡ͷ0X7B if(round(req->x)==1) Send_Data.tx[1] = 1; else if(round(req->x)==2) Send_Data.tx[1] = 2; else if(round(req->x)==0) Send_Data.tx[1] = 0,AutoRecharge=0; Send_Data.tx[2] = 0; Send_Data.tx[3] = 0; Send_Data.tx[4] = 0; Send_Data.tx[5] = 0; Send_Data.tx[6] = 0; Send_Data.tx[7] = 0; Send_Data.tx[8] = 0; Send_Data.tx[9]=Check_Sum(9,SEND_DATA_CHECK); //For the BCC check bits, see the Check_Sum function //BCCУ��λ������μ�Check_Sum���� Send_Data.tx[10]=FRAME_TAIL; //frame tail 0x7D //֡β0X7D try { Stm32_Serial.write(Send_Data.tx,sizeof (Send_Data.tx)); //Sends data to the downloader via serial port //ͨ����������λ���������� } catch (serial::IOException& e) { res->name = "false"; } if( Send_Data.tx[1]==0 ) { if(charge_set_state==0) AutoRecharge=0,res->name = "true"; else res->name = "false"; } else { if(charge_set_state==1) res->name = "true"; else res->name = "false"; } return; } ////////// 回充发布与回调 //////// /************************************** Date: January 28, 2021 Function: Serial port communication check function, packet n has a byte, the NTH -1 byte is the check bit, the NTH byte bit frame end.Bit XOR results from byte 1 to byte n-2 are compared with byte n-1, which is a BCC check Input parameter: Count_Number: Check the first few bytes of the packet 功能: 串口通讯校验函数,数据包n有个字节,第n-1个字节为校验位,第n个字节位帧尾。第1个字节到第n-2个字节数据按位异或的结果与第n-1个字节对比,即为BCC校验 输入参数: Count_Number:数据包前几个字节加入校验 mode:对发送数据还是接收数据进行校验 ***************************************/ unsigned char turn_on_robot::Check_Sum(unsigned char Count_Number,unsigned char mode) { unsigned char check_sum=0,k; if(mode==0) //Receive data mode //接收数据模式 { for(k=0;k<Count_Number;k++) { check_sum=check_sum^Receive_Data.rx[k]; //By bit or by bit //按位异或 } } if(mode==1) //Send data mode //发送数据模式 { for(k=1;k<Count_Number;k++) { check_sum=check_sum^Send_Data.tx[k]; //By bit or by bit //按位异或 } } return check_sum; //Returns the bitwise XOR result //返回按位异或结果 } //自动回充专用校验位 unsigned char turn_on_robot::Check_Sum_AutoCharge(unsigned char Count_Number,unsigned char mode) { unsigned char check_sum=0,k; if(mode==0) //Receive data mode //接收数据模式 { for(k=0;k<Count_Number;k++) { check_sum=check_sum^Receive_AutoCharge_Data.rx[k]; //By bit or by bit //按位异或 } } return check_sum; } /************************************** Date: November 18, 2021 Function: Read and verify the data sent by the lower computer frame by frame through the serial port, and then convert the data into international units 功能: 通过串口读取并逐帧校验下位机发送过来的数据,然后数据转换为国际单位 ***************************************/ bool turn_on_robot::Get_Sensor_Data_New() { short transition_16=0; //Intermediate variable //中间变量 //uint8_t i=0; uint8_t check=0,check2=0, error=1,error2=1,Receive_Data_Pr[1]; //Temporary variable to save the data of the lower machine //临时变量,保存下位机数据 static int count,count2; //Static variable for counting //静态变量,用于计数 Stm32_Serial.read(Receive_Data_Pr,sizeof(Receive_Data_Pr)); //Read the data sent by the lower computer through the serial port //通过串口读取下位机发送过来的数据 /*//View the received raw data directly and debug it for use//直接查看接收到的原始数据,调试使用 ROS_INFO("%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x", Receive_Data_Pr[0],Receive_Data_Pr[1],Receive_Data_Pr[2],Receive_Data_Pr[3],Receive_Data_Pr[4],Receive_Data_Pr[5],Receive_Data_Pr[6],Receive_Data_Pr[7], Receive_Data_Pr[8],Receive_Data_Pr[9],Receive_Data_Pr[10],Receive_Data_Pr[11],Receive_Data_Pr[12],Receive_Data_Pr[13],Receive_Data_Pr[14],Receive_Data_Pr[15], Receive_Data_Pr[16],Receive_Data_Pr[17],Receive_Data_Pr[18],Receive_Data_Pr[19],Receive_Data_Pr[20],Receive_Data_Pr[21],Receive_Data_Pr[22],Receive_Data_Pr[23]); */ Receive_Data.rx[count] = Receive_Data_Pr[0]; //Fill the array with serial data //串口数据填入数组 Receive_AutoCharge_Data.rx[count2] = Receive_Data_Pr[0]; Receive_Data.Frame_Header = Receive_Data.rx[0]; //The first part of the data is the frame header 0X7B //数据的第一位是帧头0X7B Receive_Data.Frame_Tail = Receive_Data.rx[23]; //The last bit of data is frame tail 0X7D //数据的最后一位是帧尾0X7D //接收到自动回充数据的帧头、上一个数据是24字节的帧尾,表明自动回充数据开始到来 if((Receive_Data_Pr[0] == AutoCharge_HEADER )||count2>0) count2++; else count2=0; if(Receive_Data_Pr[0] == FRAME_HEADER || count>0) //Ensure that the first data in the array is FRAME_HEADER //确保数组第一个数据为FRAME_HEADER count++; else count=0; //自动回充数据处理 if(count2 == AutoCharge_DATA_SIZE) { count2=0; if(Receive_AutoCharge_Data.rx[AutoCharge_DATA_SIZE-1]==AutoCharge_TAIL) //确认帧尾 { check2 = Check_Sum_AutoCharge(6,0);//校验位计算 if(check2 == Receive_AutoCharge_Data.rx[AutoCharge_DATA_SIZE-2]) //校验正确 { error2=0; } if(error2 == 0) //校验正确开始赋值 { transition_16 = 0; transition_16 |= Receive_AutoCharge_Data.rx[1]<<8; transition_16 |= Receive_AutoCharge_Data.rx[2]; Charging_Current = transition_16/1000+(transition_16 % 1000)*0.001; //充电电流 Red = Receive_AutoCharge_Data.rx[3]; //红外接受状态 Charging = Receive_AutoCharge_Data.rx[4];//小车充电状态 charge_set_state = Receive_AutoCharge_Data.rx[5]; check_AutoCharge_data = true; //数据成功接收标志位 } } } if(count == 24) //Verify the length of the packet //验证数据包的长度 { count=0; //Prepare for the serial port data to be refill into the array //为串口数据重新填入数组做准备 if(Receive_Data.Frame_Tail == FRAME_TAIL) //Verify the frame tail of the packet //验证数据包的帧尾 { check=Check_Sum(22,READ_DATA_CHECK); //BCC check passes or two packets are interlaced //BCC校验通过或者两组数据包交错 if(check == Receive_Data.rx[22]) { error=0; //XOR bit check successful //异或位校验成功 } if(error == 0) { /*//Check receive_data.rx for debugging use //查看Receive_Data.rx,调试使用 ROS_INFO("%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x-%x", Receive_Data.rx[0],Receive_Data.rx[1],Receive_Data.rx[2],Receive_Data.rx[3],Receive_Data.rx[4],Receive_Data.rx[5],Receive_Data.rx[6],Receive_Data.rx[7], Receive_Data.rx[8],Receive_Data.rx[9],Receive_Data.rx[10],Receive_Data.rx[11],Receive_Data.rx[12],Receive_Data.rx[13],Receive_Data.rx[14],Receive_Data.rx[15], Receive_Data.rx[16],Receive_Data.rx[17],Receive_Data.rx[18],Receive_Data.rx[19],Receive_Data.rx[20],Receive_Data.rx[21],Receive_Data.rx[22],Receive_Data.rx[23]); */ Receive_Data.Flag_Stop=Receive_Data.rx[1]; //set aside //预留位 Robot_Vel.X = Odom_Trans(Receive_Data.rx[2],Receive_Data.rx[3]); //Get the speed of the moving chassis in the X direction //获取运动底盘X方向速度 //Robot_Vel.Y = Odom_Trans(Receive_Data.rx[4],Receive_Data.rx[5]); //Get the speed of the moving chassis in the Y direction, The Y speed is only valid in the omnidirectional mobile robot chassis //获取运动底盘Y方向速度,Y速度仅在全向移动机器人底盘有效 //Robot_Vel.Z = Odom_Trans(Receive_Data.rx[6],Receive_Data.rx[7]); //Get the speed of the moving chassis in the Z direction //获取运动底盘Z方向速度 //MPU6050 stands for IMU only and does not refer to a specific model. It can be either MPU6050 or MPU9250 //Mpu6050仅代表IMU,不指代特定型号,既可以是MPU6050也可以是MPU9250 Mpu6050_Data.imu_rol = IMU_Trans(Receive_Data.rx[4],Receive_Data.rx[5]) * 0.01 * 3.14159/180; Mpu6050_Data.imu_yaw = IMU_Trans(Receive_Data.rx[6],Receive_Data.rx[7]) * 0.01 * 3.14159/180; Mpu6050_Data.accele_x_data = IMU_Trans(Receive_Data.rx[8],Receive_Data.rx[9]); //Get the X-axis acceleration of the IMU //获取IMU的X轴加速度 Mpu6050_Data.accele_y_data = IMU_Trans(Receive_Data.rx[10],Receive_Data.rx[11]); //Get the Y-axis acceleration of the IMU //获取IMU的Y轴加速度 Mpu6050_Data.accele_z_data = IMU_Trans(Receive_Data.rx[12],Receive_Data.rx[13]); //Get the Z-axis acceleration of the IMU //获取IMU的Z轴加速度 Mpu6050_Data.gyros_x_data = IMU_Trans(Receive_Data.rx[14],Receive_Data.rx[15]); //Get the X-axis angular velocity of the IMU //获取IMU的X轴角速度 Mpu6050_Data.gyros_y_data = IMU_Trans(Receive_Data.rx[16],Receive_Data.rx[17]); //Get the Y-axis angular velocity of the IMU //获取IMU的Y轴角速度 Mpu6050_Data.gyros_z_data = IMU_Trans(Receive_Data.rx[18],Receive_Data.rx[19]); //Get the Z-axis angular velocity of the IMU //获取IMU的Z轴角速度 //Linear acceleration unit conversion is related to the range of IMU initialization of STM32, where the range is ±2g=19.6m/s^2 //线性加速度单位转化,和STM32的IMU初始化的时候的量程有关,这里量程±2g=19.6m/s^2 Mpu6050.linear_acceleration.x = Mpu6050_Data.accele_x_data * 0.01 * 9.8; Mpu6050.linear_acceleration.y = Mpu6050_Data.accele_y_data * 0.01 * 9.8; Mpu6050.linear_acceleration.z = Mpu6050_Data.accele_z_data * 0.01 * 9.8; //The gyroscope unit conversion is related to the range of STM32's IMU when initialized. Here, the range of IMU's gyroscope is ±500°/s //Because the robot generally has a slow Z-axis speed, reducing the range can improve the accuracy //陀螺仪单位转化,和STM32的IMU初始化的时候的量程有关,这里IMU的陀螺仪的量程是±500°/s //因为机器人一般Z轴速度不快,降低量程可以提高精度 Mpu6050.angular_velocity.x = Mpu6050_Data.gyros_x_data * 0.01 *3.14159/180; Mpu6050.angular_velocity.y = Mpu6050_Data.gyros_y_data * 0.01 *3.14159/180; Mpu6050.angular_velocity.z = Mpu6050_Data.gyros_z_data * 0.01 *3.14159/180; //Get the battery voltage //获取电池电压 transition_16 = 0; transition_16 |= Receive_Data.rx[20]<<8; transition_16 |= Receive_Data.rx[21]; Power_voltage = transition_16/1000+(transition_16 % 1000)*0.001; //Unit conversion millivolt(mv)->volt(v) //单位转换毫伏(mv)->伏(v) return true; } } } return false; } /************************************** Date: January 28, 2021 Function: Loop access to the lower computer data and issue topics 功能: 循环获取下位机数据与发布话题 ***************************************/ void turn_on_robot::Control() { //_Last_Time = ros::Time::now(); _Last_Time = rclcpp::Node::now(); while(rclcpp::ok()) { try { //_Now = ros::Time::now(); _Now = rclcpp::Node::now(); Sampling_Time = (_Now - _Last_Time).seconds(); //Retrieves time interval, which is used to integrate velocity to obtain displacement (mileage) //获取时间间隔,用于积分速度获得位移(里程) if (true == Get_Sensor_Data_New()) //The serial port reads and verifies the data sent by the lower computer, and then the data is converted to international units //通过串口读取并校验下位机发送过来的数据,然后数据转换为国际单位 { //Robot_Pos.X+=(Robot_Vel.X * cos(Robot_Pos.Z) - Robot_Vel.Y * sin(Robot_Pos.Z)) * Sampling_Time; //Calculate the displacement in the X direction, unit: m //计算X方向的位移,单位:m //Robot_Pos.Y+=(Robot_Vel.X * sin(Robot_Pos.Z) + Robot_Vel.Y * cos(Robot_Pos.Z)) * Sampling_Time; //Calculate the displacement in the Y direction, unit: m //计算Y方向的位移,单位:m //Robot_Pos.Z+=Robot_Vel.Z * Sampling_Time; //The angular displacement about the Z axis, in rad //绕Z轴的角位移,单位:rad Robot_Pos.X+=(Robot_Vel.X * cos(Mpu6050_Data.imu_yaw)) * Sampling_Time; //Calculate the displacement in the X direction, unit: m //计算X方向的位移,单位:m Robot_Pos.Y+=(Robot_Vel.X * sin(Mpu6050_Data.imu_yaw)) * Sampling_Time; //Calculate the displacement in the Y direction, unit: m //计算Y方向的位移,单位:m //Robot_Pos.Z = 0 ; //Calculate the three-axis attitude from the IMU with the angular velocity around the three-axis and the three-axis acceleration //通过IMU绕三轴角速度与三轴加速度计算三轴姿态 Quaternion_Solution(Mpu6050.angular_velocity.x, Mpu6050.angular_velocity.y, Mpu6050.angular_velocity.z,\ Mpu6050.linear_acceleration.x, Mpu6050.linear_acceleration.y, Mpu6050.linear_acceleration.z); Publish_Odom(); //Pub the speedometer topic //发布里程计话题 Publish_ImuSensor(); //Pub the IMU topic //发布IMU话题 Publish_Voltage(); //Pub the topic of power supply voltage //发布电源电压话题 _Last_Time = _Now; //Record the time and use it to calculate the time interval //记录时间,用于计算时间间隔 } //自动回充数据话题 if(check_AutoCharge_data) { Publish_Charging(); //Pub a topic about whether the robot is charging //发布机器人是否在充电的话题 Publish_RED(); //Pub the topic whether the robot finds the infrared signal (charging station) //发布机器人是否寻找到红外信号(充电桩)的话题 Publish_ChargingCurrent(); //Pub the charging current topic //发布充电电流话题 check_AutoCharge_data = false; } rclcpp::spin_some(this->get_node_base_interface()); //The loop waits for the callback function //循环等待回调函数 } catch (const rclcpp::exceptions::RCLError & e ) { RCLCPP_ERROR(this->get_logger(),"unexpectedly failed whith %s",e.what()); } } } /************************************** Date: January 28, 2021 Function: Constructor, executed only once, for initialization 功能: 构造函数, 只执行一次,用于初始化 ***************************************/ turn_on_robot::turn_on_robot():rclcpp::Node ("wheeltec_robot") { Sampling_Time=0; Power_voltage=0; //Clear the data //清空数据 memset(&Robot_Pos, 0, sizeof(Robot_Pos)); memset(&Robot_Vel, 0, sizeof(Robot_Vel)); memset(&Receive_Data, 0, sizeof(Receive_Data)); memset(&Send_Data, 0, sizeof(Send_Data)); memset(&Mpu6050_Data, 0, sizeof(Mpu6050_Data)); //ros::NodeHandle private_nh("~"); //Create a node handle //创建节点句柄 //The private_nh.param() entry parameter corresponds to the initial value of the name of the parameter variable on the parameter server //private_nh.param()入口参数分别对应:参数服务器上的名称 参数变量名 初始值 this->declare_parameter<int>("serial_baud_rate",115200); this->declare_parameter<std::string>("usart_port_name", "/dev/ttyACM0"); this->declare_parameter<std::string>("odom_frame_id", "odom_combined"); this->declare_parameter<std::string>("robot_frame_id", "base_footprint"); this->declare_parameter<std::string>("gyro_frame_id", "gyro_link"); this->get_parameter("serial_baud_rate", serial_baud_rate);//Communicate baud rate 115200 to the lower machine //和下位机通信波特率115200 this->get_parameter("usart_port_name", usart_port_name);//Fixed serial port number //固定串口号 this->get_parameter("odom_frame_id", odom_frame_id);//The odometer topic corresponds to the parent TF coordinate //里程计话题对应父TF坐标 this->get_parameter("robot_frame_id", robot_frame_id);//The odometer topic corresponds to sub-TF coordinates //里程计话题对应子TF坐标 this->get_parameter("gyro_frame_id", gyro_frame_id);//IMU topics correspond to TF coordinates //IMU话题对应TF坐标 odom_publisher = create_publisher<nav_msgs::msg::Odometry>("odom", 2);//Create the odometer topic publisher //创建里程计话题发布者 imu_publisher = create_publisher<sensor_msgs::msg::Imu>("imu/data_raw", 2); //Create an IMU topic publisher //创建IMU话题发布者 voltage_publisher = create_publisher<std_msgs::msg::Float32>("PowerVoltage", 1);//Create a battery-voltage topic publisher //创建电池电压话题发布者 //回充发布者 Charging_publisher = create_publisher<std_msgs::msg::Bool>("robot_charging_flag", 10); Charging_current_publisher = create_publisher<std_msgs::msg::Float32>("robot_charging_current", 10); RED_publisher = create_publisher<std_msgs::msg::UInt8>("robot_red_flag", 10); //回充订阅者 Red_Vel_Sub = create_subscription<geometry_msgs::msg::Twist>( "red_vel", 10, std::bind(&turn_on_robot::Red_Vel_Callback, this, std::placeholders::_1)); Recharge_Flag_Sub = create_subscription<std_msgs::msg::Int8>( "robot_recharge_flag", 10, std::bind(&turn_on_robot::Recharge_Flag_Callback, this,std::placeholders::_1)); //回充服务提供 SetCharge_Service=this->create_service<turtlesim::srv::Spawn>\ ("/set_charge",std::bind(&turn_on_robot::Set_Charge_Callback,this, std::placeholders::_1 ,std::placeholders::_2)); //Set the velocity control command callback function //速度控制命令订阅回调函数设置 Cmd_Vel_Sub = create_subscription<geometry_msgs::msg::Twist>( "cmd_vel", 2, std::bind(&turn_on_robot::Cmd_Vel_Callback, this, _1)); RCLCPP_INFO(this->get_logger(),"wheeltec_robot Data ready"); //Prompt message //提示信息 try { //Attempts to initialize and open the serial port //尝试初始化与开启串口 Stm32_Serial.setPort(usart_port_name); //Select the serial port number to enable //选择要开启的串口号 Stm32_Serial.setBaudrate(serial_baud_rate); //Set the baud rate //设置波特率 serial::Timeout _time = serial::Timeout::simpleTimeout(2000); //Timeout //超时等待 Stm32_Serial.setTimeout(_time); Stm32_Serial.open(); //Open the serial port //开启串口 } catch (serial::IOException& e) { RCLCPP_ERROR(this->get_logger(),"wheeltec_robot can not open serial port,Please check the serial port cable! "); //If opening the serial port fails, an error message is printed //如果开启串口失败,打印错误信息 } if(Stm32_Serial.isOpen()) { RCLCPP_INFO(this->get_logger(),"wheeltec_robot serial port opened"); //Serial port opened successfully //串口开启成功提示 } } /************************************** Date: January 28, 2021 Function: Destructor, executed only once and called by the system when an object ends its life cycle 功能: 析构函数,只执行一次,当对象结束其生命周期时系统会调用这个函数 ***************************************/ turn_on_robot::~turn_on_robot() { //Sends the stop motion command to the lower machine before the turn_on_robot object ends //对象turn_on_robot结束前向下位机发送停止运动命令 Send_Data.tx[0]=0x06; Send_Data.tx[1] = FRAME_HEADER; Send_Data.tx[2] = 0; //The target velocity of the X-axis of the robot //机器人X轴的目标线速度 Send_Data.tx[4] = 0; Send_Data.tx[3] = 0; //The target velocity of the Y-axis of the robot //机器人Y轴的目标线速度 Send_Data.tx[6] = 0; Send_Data.tx[5] = 0; //The target velocity of the Z-axis of the robot //机器人Z轴的目标角速度 Send_Data.tx[8] = 0; Send_Data.tx[7] = 0; Send_Data.tx[9]=Check_Sum(9,SEND_DATA_CHECK); //Check the bits for the Check_Sum function //校验位,规则参见Check_Sum函数 Send_Data.tx[10]=0x0d; Send_Data.tx[11]=0x0a; try { Stm32_Serial.write(Send_Data.tx,sizeof (Send_Data.tx)); //Send data to the serial port //向串口发数据 } catch (serial::IOException& e) { RCLCPP_ERROR(this->get_logger(),"Unable to send data through serial port"); //If sending data fails, an error message is printed //如果发送数据失败,打印错误信息 } Stm32_Serial.close(); //Close the serial port //关闭串口 RCLCPP_INFO(this->get_logger(),"Shutting down"); //Prompt message //提示信息 } turn_on_wheeltec_robot.launch.py文件代码为: import os from pathlib import Path import launch from launch.actions import SetEnvironmentVariable from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import (DeclareLaunchArgument, GroupAction, IncludeLaunchDescription, SetEnvironmentVariable) from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration, PythonExpression from launch_ros.actions import PushRosNamespace import launch_ros.actions from launch.conditions import IfCondition from launch.conditions import UnlessCondition def generate_launch_description(): # Get the launch directory bringup_dir = get_package_share_directory('turn_on_wheeltec_robot') launch_dir = os.path.join(bringup_dir, 'launch') ekf_config = Path(get_package_share_directory('turn_on_wheeltec_robot'), 'config', 'ekf.yaml') ekf_carto_config = Path(get_package_share_directory('turn_on_wheeltec_robot'), 'config', 'ekf_carto.yaml') imu_config = Path(get_package_share_directory('turn_on_wheeltec_robot'), 'config', 'imu.yaml') carto_slam = LaunchConfiguration('carto_slam', default='false') carto_slam_dec = DeclareLaunchArgument('carto_slam',default_value='false') wheeltec_robot = IncludeLaunchDescription( PythonLaunchDescriptionSource(os.path.join(launch_dir, 'base_serial.launch.py')), ) robot_ekf = IncludeLaunchDescription( PythonLaunchDescriptionSource(os.path.join(launch_dir, 'wheeltec_ekf.launch.py')), launch_arguments={'carto_slam':carto_slam}.items(), ) base_to_link = launch_ros.actions.Node( package='tf2_ros', executable='static_transform_publisher', name='base_to_link', arguments=['0', '0', '0','0', '0','0','base_footprint','base_link'], ) base_to_gyro = launch_ros.actions.Node( package='tf2_ros', executable='static_transform_publisher', name='base_to_gyro', arguments=['0', '0', '0','0', '0','0','base_link','gyro_link'], ) imu_filter_node = launch_ros.actions.Node( package='imu_filter_madgwick', executable='imu_filter_madgwick_node', parameters=[imu_config] ) # joint_state_publisher_node = launch_ros.actions.Node( # package='joint_state_publisher', # executable='joint_state_publisher', # name='joint_state_publisher', # ) #select a robot model,the default model is mini_mec #minibot.launch.py contains commonly used robot models #launch_arguments choices:mini_mec/mini_akm/mini_tank/mini_4wd/mini_diff/mini_omni/brushless_senior_diff #!!!At the same time, you need to modify ld.add_action(minibot_type) and #ld.add_action(flagship_type) minibot_type = IncludeLaunchDescription( PythonLaunchDescriptionSource(os.path.join(launch_dir, 'robot_mode_description_minibot.launch.py')), launch_arguments={'bike_robot': 'true'}.items(), ) #robot_mode_description.launch.py contains flagship products, usually larger chassis robots #launch_arguments choices: #senior_akm/top_akm_bs/top_akm_dl #senior_mec_bs/senior_mec_dl/top_mec_bs/top_mec_dl/ mec_EightDrive_robot/flagship_mec_bs_robot/flagship_mec_dl_robot�� #senior_omni/top_omni #senior_4wd_bs_robot/senior_4wd_dl_robot/flagship_4wd_bs_robot/flagship_4wd_dl_robot/top_4wd_bs_robot/top_4wd_dl_robot #senior_diff_robot/four_wheel_diff_bs/four_wheel_diff_dl/flagship_four_wheel_diff_bs_robot/flagship_four_wheel_diff_dl_robot #!!!At the same time, you need to modify ld.add_action(flagship_type) and #ld.add_action(minibot_type) flagship_type = IncludeLaunchDescription( PythonLaunchDescriptionSource(os.path.join(launch_dir, 'robot_mode_description.launch.py')), launch_arguments={'senior_akm': 'true'}.items(), ) ld = LaunchDescription() ld.add_action(minibot_type) #ld.add_action(flagship_type) ld.add_action(carto_slam_dec) ld.add_action(wheeltec_robot) ld.add_action(base_to_link) ld.add_action(base_to_gyro) # ld.add_action(joint_state_publisher_node) ld.add_action(imu_filter_node) ld.add_action(robot_ekf) return ld base_serial.launch.py文件代码为: from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration from launch.conditions import IfCondition from launch.conditions import UnlessCondition import launch_ros.actions #def launch(launch_descriptor, argv): def generate_launch_description(): return LaunchDescription([ launch_ros.actions.Node( package='turn_on_wheeltec_robot', executable='wheeltec_robot_node', output='screen', parameters=[{'usart_port_name': '/dev/ttyACM0', 'serial_baud_rate':115200, 'robot_frame_id': 'base_footprint', 'odom_frame_id': 'odom_combined', 'cmd_vel': 'cmd_vel',}], ) ]) robot_mode_description_minibot.launch.py文件代码为: import os from ament_index_python.packages import get_package_share_directory import launch_ros.actions from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable from launch.conditions import IfCondition from launch.substitutions import LaunchConfiguration, PythonExpression from launch_ros.actions import LoadComposableNodes from launch_ros.actions import Node from launch_ros.descriptions import ComposableNode from nav2_common.launch import RewrittenYaml def generate_robot_node(robot_urdf,child): return launch_ros.actions.Node( package='robot_state_publisher', executable='robot_state_publisher', name=f'robot_state_publisher_{child}', arguments=[os.path.join(get_package_share_directory('wheeltec_robot_urdf'), 'urdf', robot_urdf)], ) def generate_static_transform_publisher_node(translation, rotation, parent, child): return launch_ros.actions.Node( package='tf2_ros', executable='static_transform_publisher', name=f'base_to_{child}', arguments=[translation[0], translation[1], translation[2], rotation[0], rotation[1], rotation[2], parent, child], ) def generate_launch_description(): bike_robot = LaunchConfiguration('bike_robot', default='false') bike_robot_ = GroupAction( condition=IfCondition(bike_robot), actions=[ generate_robot_node('xuan_bike_robot.urdf','bike_robot'), generate_static_transform_publisher_node(['0.048', '0', '0.18'], ['0', '0', '0'], 'base_link', 'laser'), generate_static_transform_publisher_node(['0.048', '0', '0.18'], ['0', '0', '0'], 'base_link', 'camera_link'), ]) # Create the launch description and populate ld = LaunchDescription() # Set environment variables # Declare the launch options #ld.add_action(declare_use_composition_cmd) # Add the actions to launch all of the localiztion nodes ld.add_action(mini_mec_) ld.add_action(mini_akm_) ld.add_action(mini_tank_) ld.add_action(mini_4wd_) ld.add_action(mini_diff_) ld.add_action(brushless_senior_diff_) ld.add_action(bike_robot_) return ld xuan_bike_robot.urdf文件代码为: <?xml version="1.0"?> <robot name="wheeltec_robot"> <link name="base_link"> <visual> <geometry> <mesh filename="file:///home/deepbot/ros-relate/wheeltec_ros2/src/wheeltec_robot_urdf/wheeltec_robot_urdf/meshes/Xuan-release.stl"scale="0.001 0.001 0.001"/> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="blue"> <color rgba="0 0 0.8 0.5"/> </material> </visual> </link> </robot>
05-14
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值