樹莓派 0W 狂想曲︰ 木牛流馬《界面》

如果只是將

W!o+ 的《小伶鼬工坊演義》︰ 一窺全豹之系統設計《關鍵》

固然我們現今可以閱讀 GrovePi 韌體的原始碼,

# GrovePi V1.2.5 韌體 I2C 讀寫流程骨幹

33 int cmd[5];
34 int index=0;
35 int flag=0;

68 void setup()
69 {
70     // Serial.begin(38400); // start serial for output
71     Wire.begin(SLAVE_ADDRESS);
72
73     Wire.onReceive(receiveData);
74     Wire.onRequest(sendData);
75         attachInterrupt(0,readPulseDust,CHANGE);
76 }

79 void loop()
80 {
81   long dur,RangeCm;
82   if(index==4)
83 {
84   flag=1;
85   //IR reciever pin set command
86   if(cmd[0]==22)
87      IR.Init(cmd[1]);
88
89   //Grove IR recieve command
90   else if(cmd[0]==21)
91   {
92      if(IR.IsDta())
93       {
94          int length= IR.Recv(dta);
95          b[0]=1;
96          for(i=0;i<20;i++)
97              b[i+1]=dta[i];
98       }
99   }
100
101 //Digital Read
102 else if(cmd[0]==1)
103   val=digitalRead(cmd[1]);
104 //Digital Write
105 else if(cmd[0]==2)
106   digitalWrite(cmd[1],cmd[2]);

646 void receiveData(int byteCount)
647 {
648     while(Wire.available())
649      {
650       if(Wire.available()==4)
651        {
652         flag=0;
653         index=0;
654                 run_once=1;
655        }
656         cmd[index++] = Wire.read();
657       }
658 }

660 // callback for sending data
661 void sendData()
662 {
663   if(cmd[0] == 1)
664     Wire.write(val);
665   if(cmd[0] == 3 || cmd[0] == 7 || cmd[0] == 56)
666     Wire.write(b, 3);
667   if(cmd[0] == 8 || cmd[0] == 20)
668     Wire.write(b, 4);
669   if(cmd[0] == 30)
670     Wire.write(b, 9);
671   if(cmd[0] == 40)
672     Wire.write(dht_b, 9);
673
674   if(cmd[0]==21)
675    {
676     Wire.write(b,21);
677     b[0]=0;
678    }
679   if(cmd[0]==dust_sensor_read_cmd)
680    {
681     Wire.write(b,4);
682         dust_latest=0;
683         cmd[0]=0;
684    }
685   if(cmd[0]==encoder_read_cmd)
686    {
687     Wire.write(enc_val,2);
688     enc_val[0]=0;
689         cmd[0]=0;
690    }
691   if(cmd[0]==flow_read_cmd)
692    {
693     Wire.write(flow_val,3);
694     flow_val[0]=0;
695         cmd[0]=0;
696    }
697
698 }


,追跡其上裝置的驅動始末,甚至可以創寫新的可連接設備。但思『架構拼圖』時,『全貌』是『關鍵』,一時過細恐泥。況且通常『應用軟體界面』 API ,實有多種多層

……

 

文字略作修改,以『GoPiGo』取代『GrovePi』,編輯新『韌體』原始碼︰

# GoPiGo fw_ver_16.ino 韌體 I2C 讀寫流程骨幹
# line 130
volatile int cmd[5],index=0,bytes_to_send=0; //I2C Message variables
byte payload[21];
unsigned char dta[20];

# line 266
//Setting up the GoPiGo
void setup()
{
    if (debug) //Enable the serial port on the GoPiGo
    {
        Serial.begin(19200);
        Serial.print("Ready");
    }

    for(int i=0;i<10;i++)
        hw_version=analogRead(7);

    if(hw_version<790)
    {
        motor2_control_pin2=13;
        right_led_pin=5;
        left_led_pin=10;
        voltage_pin=0;
    }
    attachInterrupt(0, step1, RISING); //Attach the encoders to an ISR to keep track of the wheel rotations
    attachInterrupt(1, step2, RISING);

    pinMode(motor1_control_pin1, OUTPUT); //Attach motor direction control pins
    pinMode(motor1_control_pin2, OUTPUT);
    pinMode(motor2_control_pin1, OUTPUT);
    pinMode(motor2_control_pin2, OUTPUT);
    // pinMode(left_led_pin, OUTPUT); //Attach motor direction control pins
    // pinMode(right_led_pin, OUTPUT);

    servo1.attach(5); //Set up the Servo
    //servo1.setMaximumPulse(3000);

    Wire.begin(GOPIGO_ADDR); //Set up I2C
    Wire.onReceive(receiveData);
    Wire.onRequest(sendData);

    speed1=speed2=spd;

    //IR.Init(A1);
    //Load the trim value for motor 2 from the EEPROM
    ep1=EEPROM.read(0);
    ep2=EEPROM.read(1);
    ep3=EEPROM.read(2);

    //Load the trim value of the first 2 bytes are the right signature
    if (ep1==ep_sig1 && ep2==ep_sig2)
        trim_val=ep3;
    //Disable trim if the signature is not a match
    else
        trim_val=100;

    // digitalWrite(right_led_pin,HIGH);
    // digitalWrite(left_led_pin,HIGH);
    // delay(1000);
    // digitalWrite(right_led_pin,LOW);
    // digitalWrite(left_led_pin,LOW);
    }

# line 331
//Main program loop
//IMPORTANT NOTE: Set the cmd[0] to 0 to mark that the command has been executed
// Be careful with this, because for some commands like fwd() and bwd() you'll not want the motors to stop when the GoPiGo receives any command. So most of the commands are run only once but when commands like fwd() , bwd() are running, cmd[0] goes back to the old state after the new commands are successfully run.

//FUNCTIONALITY NOTE:
// * servo::refresh() - takes .5 to 2.5 ms to complete
// * the motor interrupts have to be slower than the I2C interrupts. This has been a problem with I2C communication. The motor interrupts are of higher priority,
// so if I2C block communication is used, there is a chance of the motors interrupting them. Conflicts can still be there but very rare
void loop()
{
    //Update the speed by taking in account the trim value
    speed2_trim=int(speed2+(speed2*float(trim_val-100)/100));
    if (speed2_trim>255)
        speed2_trim=255;
    else if(speed2_trim<0)
        speed2_trim=0;

    analogWrite(motor1_speed_pin,speed1); //Write the speed to the motors
    analogWrite(motor2_speed_pin,speed2_trim);

    //LED encoder test (Manufacturing test: Not to be used by user)
    //Blink the left LED when the right wheel is rotated and the right LED when the left wheel is rotated
    if(cmd[0]==enc_test)
    {
        if(f1==1)
        {
            led_light(0,1);
            f1=0;
        }
        if(f2==1)
        {
            led_light(1,1);
            f2=0;
        }
        delay(200);
        led_light(0,0);
        led_light(1,0);
        }

# line 937
//Receive commands via I2C
void receiveData(int byteCount)
{
    while(Wire.available())
    {
        //When the buffer gets filled up with 4 bytes( the commands have to be 4 bytes in size), set the index back to 0 to read the next command
        if(Wire.available()==4)
        {
            index=0;
            if(timeout_f) //Refresh the communication time-out value
                last_t=millis();
        }
        cmd[index++] = Wire.read(); //Load the command into the buffer
    }
}

# line 953
// callback for sending data
volatile int ind=0;
void sendData()
{
     //if(timeout_f)
     // last_t=millis();
     //Sends 2 bytes back for the Ultrasonic read, voltage and firmware version
     if(bytes_to_send==2)
     {
         Wire.write(payload[ind++]);
         if(ind==2)
        {
             ind=0;
             bytes_to_send=0;
        }
     }
     else if(bytes_to_send==20)
     {
         Wire.write(payload,20);
         bytes_to_send=0;
     }
 // else if(bytes_to_send==21)
 // {
 // Wire.write(payload[ind++]);
 // if(ind==21)
 // {
 // ind=0;
 // bytes_to_send=0;
 // payload[0]=0;
 // }
 // }
     else// Send back the status flag
     {
         Wire.write(status_r);
     }
}

 

,實在沒有趣味。讀過者或認為敷衍了事,未讀過者也只得其一,都少了『比較法』學習之機會,何妨各自都能『讀樂樂』乎☆

 W!o+ 的《小伶鼬工坊演義》︰ 一窺全豹之系統設計《地圖》
 W!o+ 的《小伶鼬工坊演義》︰ 一窺全豹之系統設計《解讀》

W!o+ 的《小伶鼬工坊演義》︰ 一窺全豹之系統設計《童子問》

易童子問第一

乾,元亨利貞

童子問曰:「乾,元亨利貞」何謂也?

曰:眾辭淆亂,質諸聖。《彖》者,聖人之言也。

童子曰:然則《乾》無四德,而《文言》非聖人書乎?

曰:是魯穆姜之言也,在襄公之九年。

假使思考歐陽修為什麼寫《易童子問》?

歐陽修(1007年-1072年),字永叔,號醉翁、六一居士,諡文忠,北宋吉州廬陵(今屬江西省永豐縣)人。(歐陽修生平請參考維基百科

所著《易童子問》三卷,收錄於《歐陽文忠公集》(或簡稱《文忠集》)第七十六至七十八卷,以問答的方式表達其對於《易經》的一些見解。每個問題都以「童子問」做為開始。

文忠公是第一位對於《十翼》以及諸如「四元德」等傳統見解提出質疑與抨擊的大儒,而這些見解也影響了後世許多學者,甚至得到近現代許多學者考證的支持。

除了較為知名的《易童子問》三卷之外,易學網另外也收錄《文忠集》中其他與《易經》相關的論述,以完整呈現歐陽修對《易經》所提出的見解。

,難到不因懷疑也!『聖人』也是『人』??果能『全知』乎!!

今想 GrovePi 之『軟體架構』,當真『奇怪』耶︰

【為什麼需要 Dummy Byte ?】

dataformat

因為 SMBus 的

I2C Access Functions

long[] read_i2c_block_data( int addr, char cmd )
Block Read transaction.

write_i2c_block_data(int addr, char cmd,  long vals[])
Block Write transaction.

,需要『 char cmd 』參數!所以

………

 

 

 

 

 

 

 

 

 

樹莓派 0W 狂想曲︰ 木牛流馬《控制》

想那洛水小神龜自由自在

洛書

Turtle

L3

L2

images

子虛先生說︰昔時洛水有神龜,總於晨昏之時,彩雲滿天之際,游於洛水之波光霞影之中。興起就神足直行,左旋右轉飛舞迴旋,那時波濤不起漣漪不見,河面只隨神龜尾之上下,或粗或細或長或短或直或曲契刻成圖文。一日大禹治水偶經洛水恰遇神龜,神龜感念大禹昔日洩洪疏河之恩,特演平日最得意水畫之作,所以歷史才傳說『大禹得洛書』。

雖然作者以為子虛先生所說乃是烏有之言,然而他卻把『小海龜』繪圖法的精神描寫的活靈活現。小海龜頭的朝向決定它『前進』的方向,『【向前】【數值】 』表示向前走多少單位距離的指令,比方 forward 10,是說向前走十個單位。除了直行之外小海龜還可以『轉向』,這個轉向是依據當前之前進的方向『左轉』或是『右轉』,用『【旋轉】【角度】』表示,比方 rotate 90 是說右轉九十度, 而 rotate -90 是講左轉九十度。小海龜在網頁上的『位置』是由網頁上的 (X,Y) 座標來決定的,它的設定是『左上』(0,0)和『右下』 (600,600) 。小海龜當下的『狀態』state 是由『現在』的『位置』與『朝向角度』所一起決定的,這也就是『存上堆疊』push 與『堆疊取回』pop 存上取回指令裡所說的狀態。小海龜可以給定一個『開始』的『位置』與『朝向』,初進網頁時它在 (50,300),小海龜的頭朝右,它的角度是 0。

─── 摘自《科赫傳說!!

 

自主自動,經絡暢通心到行至,早不知何謂『控制』的也。這個『 GoPiGo 』畢竟是人造之物聽人使喚,前進、後退、左旋、右轉不得不有個『運動機制』

Servomotor

A servomotor is a rotary actuator or linear actuator that allows for precise control of angular or linear position, velocity and acceleration.[1] It consists of a suitable motor coupled to a sensor for position feedback. It also requires a relatively sophisticated controller, often a dedicated module designed specifically for use with servomotors.

Servomotors are not a specific class of motor although the term servomotor is often used to refer to a motor suitable for use in a closed-loop control system.

Servomotors are used in applications such as robotics, CNC machinery or automated manufacturing.

Industrial servomotor
The grey/green cylinder is the brush-type DC motor. The black section at the bottom contains the planetary reduction gear, and the black object on top of the motor is the optical rotary encoder for position feedback. This is the steering actuator of a large robot vehicle.

Mechanism

A servomotor is a closed-loop servomechanism that uses position feedback to control its motion and final position. The input to its control is a signal (either analogue or digital) representing the position commanded for the output shaft.

The motor is paired with some type of encoder to provide position and speed feedback. In the simplest case, only the position is measured. The measured position of the output is compared to the command position, the external input to the controller. If the output position differs from that required, an error signal is generated which then causes the motor to rotate in either direction, as needed to bring the output shaft to the appropriate position. As the positions approach, the error signal reduces to zero and the motor stops.

The very simplest servomotors use position-only sensing via a potentiometer and bang-bang control of their motor; the motor always rotates at full speed (or is stopped). This type of servomotor is not widely used in industrial motion control, but it forms the basis of the simple and cheap servos used for radio-controlled models.

More sophisticated servomotors use optical rotary encoders to measure the speed of the output shaft[2] and a variable-speed drive to control the motor speed.[3] Both of these enhancements, usually in combination with a PID control algorithm, allow the servomotor to be brought to its commanded position more quickly and more precisely, with less overshooting.[4]

 

追求更好的『控制穩定性』

PID controller

A proportional–integral–derivative controller (PID controller) is a control loop feedback mechanism (controller) commonly used in industrial control systems. A PID controller continuously calculates an error value e ( t ) {\displaystyle e(t)} e(t) as the difference between a desired setpoint and a measured process variable and applies a correction based on proportional, integral, and derivative terms (sometimes denoted P, I, and D respectively) which give their name to the controller type.

A block diagram of a PID controller in a feedback loop. r(t) is the desired process value or “set point”, and y(t) is the measured process value.

Fundamental operation

A PID controller continuously calculates an error value e(t) as the difference between a desired setpoint and a measured process variable and applies a correction based on proportional, integral, and derivative terms. The controller attempts to minimize the error over time by adjustment of a control variable  u(t), such as the position of a control valve, a damper, or the power supplied to a heating element, to a new value determined by a weighted sum:

{\displaystyle u(t)=K_{\text{p}}e(t)+K_{\text{i}}\int _{0}^{t}e(\tau )\,d\tau +K_{\text{d}}{\frac {de(t)}{dt}},}

where  {\displaystyle K_{\text{p}}} {\displaystyle K_{\text{i}}}, and  {\displaystyle K_{\text{d}}}, all non-negative, denote the coefficients for the proportional, integral, and derivative terms, respectively (sometimes denoted P, I, and D). In this model:

  • P accounts for present values of the error. For example, if the error is large and positive, the control output will also be large and positive.
  • I accounts for past values of the error. For example, if the current output is not sufficiently strong, the integral of the error will accumulate over time, and the controller will respond by applying a stronger action.
  • D accounts for possible future trends of the error, based on its current rate of change.[1]

As a PID controller relies only on the measured process variable, not on knowledge of the underlying process, it is broadly applicable.[2] By tuning the three parameters of the model, a PID controller can deal with specific process requirements. The response of the controller can be described in terms of its responsiveness to an error, the degree to which the system overshoots a setpoint, and the degree of any system oscillation. The use of the PID algorithm does not guarantee optimal control of the system or even its stability.

Some applications may require using only one or two terms to provide the appropriate system control. This is achieved by setting the other parameters to zero. A PID controller is called a PI, PD, P or I controller in the absence of the respective control actions. PI controllers are fairly common, since derivative action is sensitive to measurement noise, whereas the absence of an integral term may prevent the system from reaching its target value.

For discrete-time systems, the term PSD (proportional-summation-difference) is often used.[3]

 

因是可知小汽車『設計構想』哩☆

4.  Attach Encoders

The encoders for the GoPiGo are cut in black and look like a little wheel.  They fit on the inside of the motors, and poke through the GoPiGo acrylic chassis.  They provide feedback on speed direction traveled to the motors. Most of the time the motors will work fine without them, but they can be used to control and refine the action of the motors.

Note: Some have found that these can fall off easily.  You can secure them with a small piece of tinfoil, paper or blue ticky tacky.

If these keep falling off, just remove them for now, as they are not necessary.

Encoders ready to be attached.

Encoders ready to be attached.

Raspberry pi robot chassis

Encoders properly attached.

 

#ifndef SoftwareServo_h
#define SoftwareServo_h

#include <Arduino.h>
#include <inttypes.h>

class SoftwareServo
{
  private:
    uint8_t pin;
    uint8_t angle;       // in degrees
    uint16_t pulse0;     // pulse width in TCNT0 counts
    uint8_t min16;       // minimum pulse, 16uS units  (default is 34)
    uint8_t max16;       // maximum pulse, 16uS units, 0-4ms range (default is 150)
    class SoftwareServo *next;
    static SoftwareServo* first;
  public:
    SoftwareServo();
    uint8_t attach(int);     // attach to a pin, sets pinMode, returns 0 on failure, won't
                             // position the servo until a subsequent write() happens
    void detach();
    void write(int);         // specify the angle in degrees, 0 to 180
    uint8_t read();
    uint8_t attached();
    void setMinimumPulse(uint16_t);  // pulse length for 0 degrees in microseconds, 540uS default
    void setMaximumPulse(uint16_t);  // pulse length for 180 degrees in microseconds, 2400uS default
    static void refresh();    // must be called at least every 50ms or so to keep servo alive
                              // you can call more often, it won't happen more than once every 20ms
};

#endif

 

 

 

 

 

 

 

 

 

 

樹莓派 0W 狂想曲︰ 木牛流馬《井通》

想那『 GoPiGo 』之軟硬體設計一如『 GrovePi 』一般,如果類似的事說兩遍總覺無趣,何妨以《井通》之法為之,非但可減省文字 ,或許可得『互見』之好處耶??

如是祇給出圖文︰

Technical Specifications of the GoPiGo:

  • Operating Voltage: 7-12V
  • Current usage:
    • -> 300-500 mA (Idle with the Raspberry Pi Model B+)
    • -> 800 mA-2A (Motors, camera and servo running with the Raspberry Pi Model B+)
  • External Interfaces:
    • -> I2C– 1Port
    • -> Serial– 1 Port
    • -> Analog– 1 Port
    • -> Digital/PWM- 1Port
  • Motor controller: 
  • Encoders
    • -> 2 Optical encoders with 18 pulse counts per rotation
  • Wheel Diameter: 65mm
  • MCU: Atmega 328

 

 

 

 

予以『線索』︰

#《W!o+ 的《小伶鼬工坊演義》︰ 一窺全豹之系統設計《硬體》

劉勰《文心雕龍‧事類

讚曰︰

經籍深富,辭理遐亙。皓如江海,鬱若昆鄧。

文梓共采,瓊珠交贈。用人若己,古來無懵。

基本上『 GrovePi 』的硬體設計只有一顆『 ATmegs 328p 』單晶片處理器,此事可見之於《 GrovePi-1.5_schem.pdf 》電路圖上。

GlovePi+

據知該舊文件現今或已不存,

GrovePi-1.5_schem

,讀者可考其《新文件》,實則相類也。這事能有什麼重要的嗎?若思『防呆』的四針『連接器』設計,在其針腳定義上,統合『 I2C 』 、『 UART serial 』、『 Digital 』與『 Analog 』接法,固然是方便簡易。

假使再思『 ATmegs328p 』之『 ISP 』

In-system programming

In-system programming (ISP), also called In-Circuit Serial Programming (ICSP), is the ability of some programmable logic devices, microcontrollers, and other embedded devices to be programmed while installed in a complete system, rather than requiring the chip to be programmed prior to installing it into the system.

There are several incompatible in-system programming protocols for programming microcontroller devices such as PIC microcontrollers, AVRs, and the Parallax Propeller. ICSP has been primarily implemented by Microchip Technology for programming PIC and dsPIC devices.

The primary advantage of this feature is that it allows manufacturers of electronic devices to integrate programming and testing into a single production phase, and save money, rather than requiring a separate programming stage prior to assembling the system. This may allow manufacturers to program the chips in their own system’s production line instead of buying preprogrammed chips from a manufacturer or distributor, making it feasible to apply code or design changes in the middle of a production run.

Microcontrollers are typically soldered directly to a printed circuit board and usually do not have the circuitry or space for a large external programming cable to another computer.

Typically, chips supporting ISP have internal circuitry to generate any necessary programming voltage from the system’s normal supply voltage, and communicate with the programmer via a serial protocol. Most programmable logic devices use a variant of the JTAG protocol for ISP, in order to facilitate easier integration with automated testing procedures. Other devices usually use proprietary protocols or protocols defined by older standards. In systems complex enough to require moderately large glue logic, designers may implement a JTAG-controlled programming subsystem for non-JTAG devices such as flash memory and microcontrollers, allowing the entire programming and test procedure to be accomplished under the control of a single protocol.

An example of devices using ISP is the AVR line of micro-controllers by Atmel such as the ATmega series.

316px-Isp_headers.svg

6 & 10 pins ISP headers

───

設計,雖說是其來有自

ATmegs328p_ISP

,但是其在樹莓派『 GPIO 』定址之法,『 SPI 』界面之用

GrovePi_RPI-connector

……

 

#《W!o+ 的《小伶鼬工坊演義》︰ 一窺全豹之系統設計《韌帶》

如今我們總算取得了『 GrovePi 』軟體架構

GROVEPI-SOFTWARE-ARCHITECTURE

的第一塊關鍵拼圖 ──

……

 

,能得『自讀自解』之樂乎!!

 

 

 

 

 

 

 

 

 

樹莓派 0W 狂想曲︰ 木牛流馬《預言》

雖然 GoPiGo 已有新版本 GoPiGo2 ,從規格、軟體、文件初步比較來看大同小異。因為目前手上只有 GoPiGo1 ,且以此為範作個開始 。鑑於硬件組合與軟件安裝, GoPiGo 官網文件十分詳盡,故不再贅述︰

Congratulations on getting a GoPiGo Raspberry Pi Robot Kit! THESE ARE OLD INSTRUCTIONS — please go here for the new one!

These instructions are for GoPiGo1. If you have the GoPiGo2, please go here.

This page and the sub-pages will help walk you through getting it setup and started.  We recommend you go through each page, in the following order:

1. Assemble the GoPiGo Raspberry Pi Robot Kit. (for accessories see below)

2. Setting up the SD Card.

3. Powering Up the GoPiGo.

4. Connect to the GoPiGo.

5. Booting the GoPiGo for the first time.

After you have completed all the steps above, you can check out the Example Projects that we have made and try them out yourself or make something cool and share it with the community.

Assembly Instructions for GoPiGo Accessories

Please find the assembly instructions for each accessory in the links below:

GoPiGo Servo Kit

Raspberry Pi Camera & Ultrasonic Sensor

 

簡言之,灌好樹莓派 Raspbian 系統,git clone https://github.com/DexterInd/GoPiGo.git

Python Library

[See our guided tutorials on getting started with Python and the GoPiGo here.] (http://www.dexterindustries.com/GoPiGo/programming/python-programming-for-the-raspberry-pi-gopigo/)

Video Playlist on Getting Started with the GoPiGo and Python

This repository contains the Python library for the GoPiGo, tests programs, projects and Examples

Files:

  • gopigo.py : Main Python library to control the GoPiGo
  • basic_test_all.py : Example to test all the functions of the GoPiGO
  • setup.py : Installation file for the GoPiGo (use only if you are not using Dexter Industries SD Card)

Folders:

  • Examples : Example programs and projects for the GoPiGo
  • tests : Test program for testing the individual subsystems of the GoPiGo
  • other_scripts: Smaller programs to check multiple sub-system functionality

 GoPiGo

This repository contains source code, firmware and design materials for the GoPiGo.

 GoPiGo

 

然後 cd /GoPiGo/Setup , sudo ./install.sh 就行。

如果讀者先知

#!/usr/bin/env python
from __future__ import print_function
from __future__ import division
# the above lines are meant for Python3 compatibility.
# they force the use of Python3 functionality for print()
# and the integer division
# mind your parentheses!
 
########################################################################
# This library is used for communicating with the GoPiGo.
# http://www.dexterindustries.com/GoPiGo/
# History
# ————————————————
# Author Date Comments
# Karan 30 March 14 Initial Authoring
# 02 July 14 Removed bugs and some features added (v0.9)
# 26 Aug 14 Code commenting and cleanup
# 07 June 16 DHT example added
”’
## License
GoPiGo for the Raspberry Pi: an open source robotics platform for the Raspberry Pi.
Copyright (C) 2017 Dexter Industries
 
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
 
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
 
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/gpl-3.0.txt>.
”’
#
########################################################################
 
import sys
import time
import math
import struct
import subprocess
 
WHEEL_RAD=3.25
WHEEL_CIRC=2*math.pi*WHEEL_RAD
PPR = 18 # encoder Pulses Per Revolution
 
if sys.platform == uwp:
import winrt_smbus as smbus
bus = smbus.SMBus(1)
else:
import RPi.GPIO as GPIO
import smbus
 
# for RPI version 1, use “bus = smbus.SMBus(0)”
rev = GPIO.RPI_REVISION
if rev == 2 or rev == 3:
bus = smbus.SMBus(1)
else:
bus = smbus.SMBus(0)

 

是『小汽車』控制的『核心程式庫』,或想複習『 I2C 』乎?

假使預知『小汽車』行動,一如『小海龜』繪圖,是否很快樂耶☆

L4K ︰ Logo 神龜之故鄉!!

L4K ︰ Python Turtle 《一》

L4K ︰ 通往 Python 的道路
 

 

 

 

 

 

 

 

樹莓派 0W 狂想曲︰ 木牛流馬《銜接》

朋友好奇的問我說︰今天『小汽車』之 DIY 組件這麼多種,為什麼獨選『 GoPiGo 』呢?

Technical Specifications of the GoPiGo:

  • Operating Voltage: 7-12V
  • Current usage:
    • -> 300-500 mA (Idle with the Raspberry Pi Model B+)
    • -> 800 mA-2A (Motors, camera and servo running with the Raspberry Pi Model B+)
  • External Interfaces:
    • -> I2C– 1Port
    • -> Serial– 1 Port
    • -> Analog– 1 Port
    • -> Digital/PWM- 1Port
  • Motor controller: 
  • Encoders
    • -> 2 Optical encoders with 18 pulse counts per rotation
  • Wheel Diameter: 65mm
  • MCU: Atmega 328

More:

Latest Design on Github.

Hardware and Port Description

The GoPiGo is stacked on top of the Raspberry Pi without the need for any other connections. Communication between the two occurs over the I2C interface. You can connect motors and sensors to the GoPiGo.

The GoPiGo has 4 ports on it on which various Grove Sensors can be connected. There is an Analog, Digital, Serial and I2C port on the GoPiGo. There is also a connector to connect the Servo motors and another connector to connect upto 3 line sensors on the GoPiGo.

All the motor control and sensor I/O on the GoPiGo is done by an ATMEGA328 microcontroller on the GoPiGo. The microcontroller acts as an interpreter between the Raspberry Pi and the GoPiGo. It sends, receives, and executes commands sent by the RaspberryPi.

In addition, the GoPiGo allows you the Raspberry Pi to access some Grove sensors directly. The Raspberry Pi has an I2C Bus by which sensors connected to the I2C Ports can be directly accessed.

GoPiGo top side

The GoPiGo has 2 optical encoders on the bottom side of the PCB that are used to track the movement of the wheels and help the GoPiGo move in a straight line.

GoPiGo bottom

Here is the port description for the GoPiGo2:

GoPiGo2 port description top side

GoPiGo2 port description bottom side

Have a question or a suggestion?  Go check out our support page here or post it on the forums here

其實這早在作者寫『 GrovePi 』主題序列文本時就已決定了,由於『 GrovePi 』涉及許多不同領域之技術內容,而且考慮從零說起,或可嘉惠更多讀者的吧!因此要談『聰明物件』得講『神經網路』 ,結果是越寫越長哩。但思不及於『光的世界』與『影像處理』,如何實現『AI 小汽車』呀?此所以當時擱筆,真作繭自縛也!!