もっと部品代を安くできないかと、マイコンをPICに置き換えて考え中・・・さらに赤外線リモコンで動作するようにしたい。

回路図

パターン図

部品一覧 もくろみほど安くはならない・・・できれば1000円以内にしたい



プログラムはXC8で、geminiで生成させたものをベースに作成。ソフトウェアPWMを使用したけど何とか歩く。
//--------------------------------------------------------------------------
// OTTO by PIC16F18313 2025/10/30
//--------------------------------------------------------------------------
#include <xc.h>
#define _XTAL_FREQ 32000000UL
// コンフィギュレーションビット設定 (内部32MHzクロックを想定)
// CONFIG1
#pragma config FEXTOSC = OFF // FEXTOSC External Oscillator mode Selection bits (Oscillator not enabled)
#pragma config RSTOSC = HFINT32 // Power-up default value for COSC bits (HFINTOSC with 2x PLL (32MHz))
#pragma config CLKOUTEN = OFF // Clock Out Enable bit (CLKOUT function is disabled; I/O or oscillator function on OSC2)
#pragma config CSWEN = OFF // Clock Switch Enable bit (The NOSC and NDIV bits cannot be changed by user software)
#pragma config FCMEN = OFF // Fail-Safe Clock Monitor Enable (Fail-Safe Clock Monitor is disabled)
// CONFIG2
#pragma config MCLRE = OFF // Master Clear Enable bit (MCLR/VPP pin function is MCLR; Weak pull-up enabled )
#pragma config PWRTE = OFF // Power-up Timer Enable bit (PWRT disabled)
#pragma config WDTE = OFF // Watchdog Timer Enable bits (WDT disabled; SWDTEN is ignored)
#pragma config LPBOREN = OFF // Low-power BOR enable bit (ULPBOR disabled)
#pragma config BOREN = OFF // Brown-out Reset Enable bits (Brown-out Reset disabled)
#pragma config BORV = LOW // Brown-out Reset Voltage selection bit (Brown-out voltage (Vbor) set to 2.45V)
#pragma config PPS1WAY = OFF // PPSLOCK bit One-Way Set Enable bit (The PPSLOCK bit can be set and cleared repeatedly (subject to the unlock sequence))
#pragma config STVREN = OFF // Stack Overflow/Underflow Reset Enable bit (Stack Overflow or Underflow will not cause a Reset)
#pragma config DEBUG = OFF // Debugger enable bit (Background debugger disabled)
// CONFIG3
#pragma config WRT = OFF // User NVM self-write protection bits (Write protection off)
#pragma config LVP = OFF // Low Voltage Programming Enable bit (HV on MCLR/VPP must be used for programming.)
// CONFIG4
#pragma config CP = OFF // User NVM Program Memory Code Protection bit (User NVM code protection disabled)
#pragma config CPD = OFF // Data NVM Memory Code Protection bit (Data NVM code protection disabled)
// -----------------------------------------------------------------------------
// グローバル変数
// -----------------------------------------------------------------------------
// 4つのサーボのパルス幅データ (100us単位のカウント数: 1000us/100us=10 ? 2000us/100us=20)
volatile unsigned char servo_pulse_count[4] = {15, 15, 15, 15}; // 15: 1.5ms (ニュートラル)
// ソフトウェアPWM用カウンタ (0?199で20ms周期を形成)
volatile unsigned char soft_pwm_counter_100us = 0;
// -----------------------------------------------------------------------------
// 初期化関数
// -----------------------------------------------------------------------------
void Initialize_System(void) {
// 1. クロック設定 (内部32MHz)
OSCCON1 = 0b01100000; // NOSC = 110 (HFINTOSC), NDIV = 0000 (FOSC=32MHz)
// 2. I/Oピン設定
ANSELA = 0x00; // PORTAを全てデジタル入出力に設定
TRISA = 0x00; // PORTAの全てを出力に設定
LATA = 0x00; // 初期状態をLOWに
// 不要な周辺モジュールの無効化
CM1CON0 = 0x00; // コンパレータ1無効
DACCON0bits.DAC1EN = 0; // DACを無効化
// 3. Timer 0 設定 - ソフトウェアPWM用 (100us割り込み)
// TMR0リロード値: 65536 - 100 = 65436 (0xFEFC)
TMR0H = 0xFE;
TMR0L = 0xFC;
T0CON1 = 0b01001000; // T0CS=010 (FOSC/4), T0CKPS=1000 (Prescaler 1:8)
T0CON0 = 0b10000000; // T0EN=1, 16bitモード
// 4. 割り込み設定
PIR0bits.TMR0IF = 0; // TMR0割り込みフラグクリア
PIE0bits.TMR0IE = 1; // TMR0割り込み有効化
INTCONbits.PEIE = 1; // 周辺割り込み有効化
INTCONbits.GIE = 1; // 全体割り込み有効化
}
// -----------------------------------------------------------------------------
// 割り込みサービスルーチン (ISR)
// -----------------------------------------------------------------------------
void __interrupt() ISR(void) {
// TMR0割り込み処理 (100usごと)
if (PIR0bits.TMR0IF) {
PIR0bits.TMR0IF = 0; // 割り込みフラグクリア
// TMR0リロード (100us周期維持)
TMR0H = 0xFE;
TMR0L = 0xFC;
soft_pwm_counter_100us++;
// 20ms (200カウント) 周期の開始
if (soft_pwm_counter_100us >= 200) {
soft_pwm_counter_100us = 0;
// 周期開始時に全てのサーボピンをHIGHにする
LATAbits.LATA1 = 1; // Servo 1 HIGH
LATAbits.LATA2 = 1; // Servo 2 HIGH
LATAbits.LATA0 = 1; // Servo 3 HIGH
LATAbits.LATA4 = 1; // Servo 4 HIGH
}
// ソフトウェアPWMのLOWへの切り替え判定
// カウンタ値がパルス幅の目標カウント数を超えたらLOWに設定
// 例: pulse_count[0]=15 (1.5ms) の場合、カウンタが15になったらLOW
if (soft_pwm_counter_100us == servo_pulse_count[0]) {
LATAbits.LATA1 = 0; // Servo 1 LOW
}
if (soft_pwm_counter_100us == servo_pulse_count[1]) {
LATAbits.LATA2 = 0; // Servo 2 LOW
}
if (soft_pwm_counter_100us == servo_pulse_count[2]) {
LATAbits.LATA0 = 0; // Servo 3 LOW
}
if (soft_pwm_counter_100us == servo_pulse_count[3]) {
LATAbits.LATA4 = 0; // Servo 4 LOW
}
}
}
// -----------------------------------------------------------------------------
// 角度設定関数 (グローバルスコープ)
// -----------------------------------------------------------------------------
/**
* @brief サーボのパルス幅を設定する
* @param servo_num サーボ番号 (0?3)
* @param pulse_us パルス幅 (1000us?2000us)
*/
void set_servo_pulse(unsigned char servo_num, unsigned int pulse_us) {
unsigned char pulse_count;
// 範囲チェック (1000us?2000usにクランプ)
if (pulse_us < 500) pulse_us = 500;
if (pulse_us > 2400) pulse_us = 2400;
// us単位から100us単位のカウント数に変換
// 1000us -> 10, 1500us -> 15, 2000us -> 20
pulse_count = (unsigned char)(pulse_us / 100);
if (servo_num <= 3) {
// グローバル変数を更新 (ISRが次周期で参照)
servo_pulse_count[servo_num] = pulse_count;
}
}
// -----------------------------------------------------------------------------
// 角度指定関数 (グローバルスコープ)
// -----------------------------------------------------------------------------
/**
* @brief サーボモータを指定角度で動かす
* @param servo_num サーボ番号 (0?3)
* @param angle_deg 角度 (0?180度)
*/
#define MIN_PULSE_US 500 // ★ SG90の最小パルス幅 (500us付近から調整)
#define MAX_PULSE_US 2400 // ★ SG90の最大パルス幅 (2500us付近まで広げてみる)
#define PULSE_RANGE (MAX_PULSE_US - MIN_PULSE_US) // 2000us
#define ANGLE_RANGE 180 // 180度
void set_servo_angle(unsigned char servo_num, unsigned int angle_deg) {
unsigned int pulse_us;
// 範囲チェック (0?180度にクランプ)
if (angle_deg > ANGLE_RANGE) angle_deg = ANGLE_RANGE;
// pulse_us = (angle_deg * PULSE_RANGE) / ANGLE_RANGE + MIN_PULSE_US
// pulse_us = (angle_deg * 1900) / 180 + 500
// 2000/180を約分して 190/18 にします
pulse_us = (angle_deg * 190) / 18 + MIN_PULSE_US;
// パルス幅を us 単位で設定
set_servo_pulse(servo_num, pulse_us);
}
void my_delay_ms(unsigned int t){
for(unsigned int i=0; i<t;i++)
__delay_us(950);
}
#define LL 0
#define RL 1
#define LF 2
#define RF 3
#define LLS 100 // 直立時のサーボ角度
#define RLS 90
#define LFS 90
#define RFS 100
int LLN,RLN,LFN,RFN;
LLN=LLS; RLN=RLS; LFN=LFS; RFN=RFS;
void upright(){
set_servo_angle( LL,LLS);
set_servo_angle( RL,RLS);
set_servo_angle( LF,LFS);
set_servo_angle( RF,RFS);
}
void forward_walk(unsigned int step_time){
set_servo_angle( RF, RFS - 30 );
set_servo_angle( LF, LFS - 15 );
my_delay_ms(step_time);
set_servo_angle( LL, LLS + 25 );
set_servo_angle( RL, RLS + 25 );
my_delay_ms(step_time);
set_servo_angle( LF, LFS + 30 );
set_servo_angle( RF, RFS + 15 );
my_delay_ms(step_time);
set_servo_angle( LL, LLS - 25 );
set_servo_angle( RL, RLS - 25 );
my_delay_ms(step_time);
}
void angle_to_angle( unsigned char servo1, unsigned int start1, unsigned int end1,unsigned int ms){
unsigned int deg;
for(deg=start1; deg<=end1; deg+=1){
set_servo_angle( servo1,deg);
my_delay_ms(ms);
}
}
void forward_walk2(unsigned int step_time){
angle_to_angle( RF, RFN , RFN - 30, 50);
//angle_to_angle( LF, LFN, LFN - 15, 50 );
RFN = RFN -30;
//LFN = LFN -15;
my_delay_ms(step_time);
angle_to_angle( RF, RFN , RFN + 30, 50);
//angle_to_angle( LF, LFN, LFN + 15, 50 );
RFN = RFN +30;
//LFN = LFN +15;
my_delay_ms(step_time);
}
// -----------------------------------------------------------------------------
// メイン関数
// -----------------------------------------------------------------------------
void main(void) {
Initialize_System();
upright();
my_delay_ms(2000);
while (1) {
LATAbits.LATA5 = 0; // LED ON
forward_walk(300);
LATAbits.LATA5 = 1; // LED OFF
forward_walk(300);
}
}
赤外線はこれから・・・