Введение:
В этом уроке мы дополним робота QUADRUPED модулем ИК-приёмник и будем управлять направлением и скоростью движения робота с помощью ИК-пульта.
Скорость и направление движения робота будет зависеть от нажатой клавиши на пульте. Робот сможет выполнять такие команды как движение вперёд или назад, с заворотом или без, разворот на месте влево или вправо.
Видео:
Waiting...
Нам понадобится:
- Обучающий набор «QUADRUPED» x1 шт.
- Trema ИК-приёмник х1шт;
- ИК-пульт х1шт;
Библиотеки:
Для реализации проекта нам необходимо установить библиотеки:
- Библиотека iarduino_IR_RX - для работы с ИК-приёмниками/передатчиками;
- Библиотеки SoftwareSerial и Servo входят в базовый набор Arduino IDE и не требуют установки.
О том как устанавливать библиотеки, Вы можете ознакомиться на странице Wiki - Установка библиотек в Arduino IDE.
Схема подключения ИК-приёмника:
Trema ИК-приёмник | Trema Shield |
---|---|
вывод G | чёрная колодка "Земля" |
вывод V | красная колодка "+5V" |
вывод S | 12 цифровой вывод (D10) |
Вы можете изменить вывод D12 для подключения ИК-приёмника на любой другой, указав его в скетче при определении константы IR
.
Схема подключения робота QUADRUPED:
Соберите механику, подключите Trema Shield, сервоприводы и откалибруйте робота, как это описано на странице Сборка QUADRUPED. Электроника + Калибровка. Далее на боковую панель установите ИК-приёмник.
Сервоприводы | Trema Shield | |
---|---|---|
1 конечность | Горизонтальный сустав (№ 0) | вывод 4 на белой колодке |
Вертикальный сустав (№ 1) | вывод 5 на белой колодке | |
2 конечность | Горизонтальный сустав (№ 2) | вывод 6 на белой колодке |
Вертикальный сустав (№ 3) | вывод 7 на белой колодке | |
3 конечность | Горизонтальный сустав (№ 4) | вывод 8 на белой колодке |
Вертикальный сустав (№ 5) | вывод 9 на белой колодке | |
4 конечность | Горизонтальный сустав (№ 6) | вывод 10 на белой колодке |
Вертикальный сустав (№ 7) | вывод 11 на белой колодке |
Вы можете изменить выводы 4-11 для подключения сервоприводов на любые другие, указав их в скетче при объявлении массива объектов PIN_SERVO[8]
. Трехпроводные шлейфы сервоприводов устанавливаются следующим образом:
- Оранжевый провод подключается к выводу на белой колодке.
- Красный провод подключается к выводу на красной колодке.
- Коричневый провод подключается к выводу на чёрной колодке.
Код программы для чтения сигналов с пульта:
#include "iarduino_IR_RX.h" // Подключаем библиотеку для работы с ИК-приёмником iarduino_IR_RX IR(12); // Объявляем объект IR и указываем вывод, к которому подключён ИК-приёмник void setup() { Serial.begin(9600); // Инициируем передачу данных в монитор порта на скорости 9600 бит/сек IR.begin(); // Инициируем работу с ИК-приёмником } void loop() { // Если в буфере имеются данные, принятые с пульта (удерживается кнопка), то выводим код нажатой кнопки if (IR.check(true)) Serial.println(IR.data, HEX); }
Данный скетч пригодится вам в том случае, если вы решите взять любой другой ИК-пульт вместо нашего. В этом случае вам надо будет определить коды кнопок, используя данный скетч, а затем указать их уже в основном коде QUADRUPED, там где указана функция IR.data
.
Код программы для робота QUADRUPED:
#define ROTATION_MOVING 0 // Определяем константу для походки: ПОВОРОТ #define NORMAL_MOVING 1 // Определяем константу для походки: ОБЫЧНАЯ ХОТЬБА #define SMOOTH_MOVING 2 // Определяем константу для походки: ПЛАВНАЯ ХОТЬБА #define GO_LEFT_FORWARD 1 // Определяем константу для движения влево-вверх #define GO_FORWARD 2 // Определяем константу для движения вверх #define GO_RIGHT_FORWARD 3 // Определяем константу для движения вправо-вверх #define GO_LEFT 4 // Определяем константу для движения влево #define STOP 5 // Определяем константу для движения стоп #define GO_RIGHT 6 // Определяем константу для движения вправо #define GO_LEFT_BACKWARD 7 // Определяем константу для движения влево-вниз #define GO_BACKWARD 8 // Определяем константу для движения вниз #define GO_RIGHT_BACKWARD 9 // Определяем константу для движения вправо-вниз #define GO_UP 10 // Определяем константу для положительного изменения высоты #define GO_DOWN 11 // Определяем константу для отрицательного изменения высоты #define SPEED_DELAY 8 // Определяем константу обратно пропорциональную скорости движения (чем больше значение, тем медленнее скорость) #define IR_SIGNAL_WAITING_TIME 100 // Определяем константу времени ожидания прихода пакета от ИК-пульта #define JOINT_CENTRAL_POS 0 // Определяем константу центрального положения всех суставов #define HORIZONTAL_JOINT 0 // Определяем константу определения типа суставов: ГОРИЗОНТАЛЬНЫЕ #define VERTICAL_JOINT 1 // Определяем константу определения типа суставов: ВЕРТИКАЛЬНЫЕ // Подключаем библиотеки: #include "Servo.h" // Подключаем библиотеку Servo, для работы с сервоприводами. #include "iarduino_IR_RX.h" // Подключаем библиотеку для работы с ИК-приёмником iarduino_IR_RX IR(12); // Объявляем объект IR, с указанием вывода к которому подключён ИК-приёмник Servo OBJ_SERVO[8]; // Создаём массив, каждый элемент которого является объектом библиотеки Servo. Цифры в комментарии указывают на № сервопривода // Определяем сервы: Г В Г В Г В Г В // Буквы в комментарии указывают на плоскость вращения сервопривода (Горизонтальная / Вертикальная) const uint8_t PIN_SERVO[8] = { 4, 5, 6, 7, 8, 9, 10, 11 }; // Определяем массив хранящий номера выводов к которым подключены сервоприводы (можно менять) const int CENTR_ANGLE[8] = { 49, 111, 104, 126, 109, 129, 74, 131 }; // Определяем массив хранящий углы в градусах, при которых сервоприводы находятся в центральном положении (КОРРЕКТИРУЕТСЯ В КАЛИБРОВОЧНОМ СКЕТЧЕ) const int MIN_ANGLE[8] = { 50, 30, 50, 30, 50, 30, 50, 30 }; // Определяем массив хранящий углы в градусах, на которые отклоняются сервоприводы от центрального положения назад или вниз const int MAX_ANGLE[8] = { 50, 40, 50, 40, 50, 40, 50, 40 }; // Определяем массив хранящий углы в градусах, на которые отклоняются сервоприводы от центрального положения вперёд или вверх // Определяем дополнительные переменные: uint8_t VarPosition = 0; // Текущая позиция походки от 0 до 255 (чем быстрее меняется значение тем выше скорость) int8_t VarTurning = 0; // Определяем переменную (поворот ) для пересчета размера шага в градусах поворота сервоприводов (-50 - влево ... 0 - прямо ... +50 вправо) int8_t VarHeightForMoving = 0; // Определяем переменную высоты корпуса относительно центрального положения для передвижения (0% - нижняя точка, 100% - верхняя точка) int8_t VarHeightForUpDown = 0; // Определяем переменную высоты корпуса относительно центрального положения для подъёма-опускания корпуса (-100 - нижняя точка, +100 - верхняя точка) uint8_t Flg = 0; // Флаг нажатой кнопки uint32_t FlgTime; // Флаг начала отправки пакетов // Объявляем функции: void joint_move_func ( uint8_t, bool, int8_t ); // Объявляем Функцию установки одного сустава в значение от -100 до 100 void limb_step_func ( uint8_t, uint8_t, int, int ); // Объявляем Функцию установки одной конечности в положение от 0 до 255 void gait_func ( uint8_t, uint8_t, int, int ); // Объявляем Функцию установки всех конечностей в положение от 0 до 255 void free_limb_func ( void ); // Объявляем Функцию ослабления всех суставов void centr_limb_func ( void ); // Объявляем Функцию установки всех суставов в центральное положение void setup(){ // Инициируем работу с ИК-приёмником IR.begin(); // Освобождаем суставы free_limb_func(); // Выставляем все конечности в центральное положение centr_limb_func(); } void loop(){ // Если с пульта приходят пакеты, то считываем код кнопки, который был нажат if (IR.check(true)) { // Флаг времени кнопки if (IR.data == 0xFFA25D) { FlgTime = millis(); Flg = GO_LEFT_FORWARD; } if (IR.data == 0xFF629D) { FlgTime = millis(); Flg = GO_FORWARD; } if (IR.data == 0xFFE21D) { FlgTime = millis(); Flg = GO_RIGHT_FORWARD; } if (IR.data == 0xFF22DD) { FlgTime = millis(); Flg = GO_LEFT; } if (IR.data == 0xFFC23D) { FlgTime = millis(); Flg = GO_RIGHT; } if (IR.data == 0xFFE01F) { FlgTime = millis(); Flg = GO_LEFT_BACKWARD; } if (IR.data == 0xFFA857) { FlgTime = millis(); Flg = GO_BACKWARD; } if (IR.data == 0xFF906F) { FlgTime = millis(); Flg = GO_RIGHT_BACKWARD; } if (IR.data == 0xFFB04F) { FlgTime = millis(); Flg = GO_UP; } if (IR.data == 0xFF9867) { FlgTime = millis(); Flg = GO_DOWN; } } // Если millis() переполнен, то сбрасываем флаг в ноль if (FlgTime > millis()) FlgTime = 0; // Если пакеты с пульта приходят в течении 100 мс, то if ((FlgTime + IR_SIGNAL_WAITING_TIME) > millis()) { // выполняем код в теле оператора каждые SPEED_DELAY миллисекунд if(millis() % SPEED_DELAY == 0){ switch (Flg) { // Скорость движения Отклонение от центра Функция движения QUADRUPED в плоскости case GO_LEFT_FORWARD: VarPosition += 2; VarTurning = -50; gait_func( NORMAL_MOVING, VarPosition, VarTurning, VarHeightForMoving); break; case GO_FORWARD: VarPosition += 2; VarTurning = 0; gait_func( NORMAL_MOVING, VarPosition, VarTurning, VarHeightForMoving); break; case GO_RIGHT_FORWARD: VarPosition += 2; VarTurning = 50; gait_func( NORMAL_MOVING, VarPosition, VarTurning, VarHeightForMoving); break; case GO_LEFT: VarPosition -= 2; VarTurning = 0; gait_func( ROTATION_MOVING, VarPosition, VarTurning, VarHeightForMoving); break; case GO_RIGHT: VarPosition += 2; VarTurning = 0; gait_func( ROTATION_MOVING, VarPosition, VarTurning, VarHeightForMoving); break; case GO_LEFT_BACKWARD: VarPosition -= 2; VarTurning = -50; gait_func( NORMAL_MOVING, VarPosition, VarTurning, VarHeightForMoving); break; case GO_BACKWARD: VarPosition -= 2; VarTurning = 0; gait_func( NORMAL_MOVING, VarPosition, VarTurning, VarHeightForMoving); break; case GO_RIGHT_BACKWARD: VarPosition -= 2; VarTurning = 50; gait_func( NORMAL_MOVING, VarPosition, VarTurning, VarHeightForMoving); break; // Увеличиваем высоту корпуса если высота больше 100%, то оставить высоту = 100% Переопределяем диапазон высоты для функции движения вверх-вниз case GO_UP: VarHeightForMoving += 1; if(VarHeightForMoving > 100) VarHeightForMoving = 100; VarHeightForUpDown = map(VarHeightForMoving, 0, 100, 100, -100); // Задаём в цикле всем вертикальным суставам изменить высоту на значение VarHeightForUpDown (от 100 (нижняя точка) до -100 (верхняя точка)) for (int LimbNumber = 1; LimbNumber < 5; LimbNumber++) joint_move_func(LimbNumber, VERTICAL_JOINT, VarHeightForUpDown); break; // Уменьшаем высоту корпуса если высота меньше 0%, то оставить высоту = 100% Переопределяем диапазон высоты для функции движения вверх-вниз case GO_DOWN: VarHeightForMoving -= 1; if(VarHeightForMoving < 0 ) VarHeightForMoving = 0; VarHeightForUpDown = map(VarHeightForMoving, 0, 100, 100, -100); // Задаём в цикле всем вертикальным суставам изменить высоту на значение VarHeightForUpDown (от 100 (нижняя точка) до -100 (верхняя точка)) for (int LimbNumber = 1; LimbNumber < 5; LimbNumber++) joint_move_func(LimbNumber, VERTICAL_JOINT, VarHeightForUpDown); break; } } } } // Функция освобождения конечностей: void free_limb_func(void){ // В цикле отключаем все сервоприводы и отключаем подачу сигналов на выводы for(uint8_t ServoNumber = 0; ServoNumber < 8; ServoNumber++){ OBJ_SERVO[ServoNumber].detach(); digitalWrite(PIN_SERVO[ServoNumber],LOW); } } // Функция установки всех суставов конечностей в центральное положение: void centr_limb_func(void){ // В цикле устанавливаем горизонтальные и вертикальные суставы в центральное положение for(uint8_t LimbNumber = 1; LimbNumber <= 4; LimbNumber++){ joint_move_func(LimbNumber,HORIZONTAL_JOINT,JOINT_CENTRAL_POS); joint_move_func(LimbNumber,VERTICAL_JOINT, JOINT_CENTRAL_POS); } } // Функция установки одного сустава конечности в значение от -100 до 100: // Где «LimbNumber» - номер конечности (1-4), «JointType» - тип сустава (0-гор. / 1-верт.), «JointPos» - положение сустава (-100 - внизу-сзади / +100 - вверху-спереди) void joint_move_func(uint8_t LimbNumber, bool JointType, int8_t JointPos){ // Определяем № сервопривода по № конечности (LimbNumber-1) и типу сустава (JointType) uint8_t ServoNumber = (LimbNumber - 1) * 2 + JointType; // Определяем переменную (k) для хранения экстремумов int k = 0; // Определяем переменную (j) для хранения экстремумов int j = JointPos? CENTR_ANGLE[ServoNumber]:0; // Находим (k) - максимально допустимое значение для аргумента (JointPos). Находим (j) - максимально допустимый угол в градусах. if(JointPos > 0){ k = +100; if( LimbNumber % 2 == 0 || ServoNumber % 2 == 1 ){ j -= MAX_ANGLE[ServoNumber]; } else { j += MAX_ANGLE[ServoNumber]; } } // Находим (k) - минимально допустимое значение для аргумента (JointPos). Находим (j) - минимально допустимый угол в градусах. if(JointPos < 0){ k = -100; // для нечётных конечностей if( LimbNumber % 2 == 1 && ServoNumber % 2 == 0 ){ j -= MIN_ANGLE[ServoNumber]; } // для чётных конечностей else { j += MIN_ANGLE[ServoNumber]; } } // Подключаем объект (OBJ_SERVO), работающий с сервоприводом (ServoNumber) к выводу (PIN_SERVO[ServoNumber]) if(!OBJ_SERVO[ServoNumber].attached()) OBJ_SERVO[ServoNumber].attach(PIN_SERVO[ServoNumber]); // Устанавливаем сервопривод (ServoNumber) в угол, находящийся между центральным положением (CENTR_ANGLE[ServoNumber]) и экстремумом (j) OBJ_SERVO[ServoNumber].write(map(JointPos, 0, k, CENTR_ANGLE[ServoNumber], j)); } // Функция установки одной конечности в положение от 0 до 255: // Где «LimbNumber» - номер конечности (1-4), «LimbPos» - позиция конечности (0-255), «HorizontalJoint» - поворот горизонтального сустава (-100 +100), «VerticalJoint» - высота вертикального сустава (0-100%) void limb_step_func(uint8_t LimbNumber, uint8_t LimbPos, int HorizontalJoint, int VerticalJoint){ // Определяем переменную для хранения позиции горизонтальной конечности int LimbHorizMoving; // Определяем переменную для хранения позиции вертикальной конечности int LimbVertMoving; if(LimbPos < 225){LimbHorizMoving = map(LimbPos, 0, 212, +100, -100);}else // Сустав конечности поворачивается назад (+100 >>> -100) {LimbHorizMoving = map(LimbPos, 225, 255, -100, +100);} // Сустав конечности поворачивается вперёд (-100 >>> +100) if(LimbPos < 225){LimbVertMoving = -100; }else // Сустав конечности опущен (-100) if(LimbPos < 235){LimbVertMoving = map(LimbPos, 225, 235, -100, +100);}else // Сустав конечности поднимается вверх (-100 >>> +100) if(LimbPos < 245){LimbVertMoving = 100; }else // Сустав конечности поднят (+100) {LimbVertMoving = map(LimbPos, 245, 255, +100, -100);} // Сустав конечности опускается вниз (+100 >>> -100) // Ограничиваем угол (LimbHorizMoving) горизонтального сустава левых конечностей (поворот влево) if(HorizontalJoint < 0 && LimbNumber % 2 == 1){ LimbHorizMoving = map(LimbHorizMoving, -100, +100, -(100 + HorizontalJoint) , 100 + HorizontalJoint); } // Ограничиваем угол (LimbHorizMoving) горизонтального сустава правых конечностей (поворот вправо) if(HorizontalJoint > 0 && LimbNumber % 2 == 0){ LimbHorizMoving = map(LimbHorizMoving, -100, +100, -(100 - HorizontalJoint) , 100 - HorizontalJoint); } // Ограничиваем угол (LimbVertMoving) вертикального сустава любых конечностей (высота хексапода) LimbVertMoving = map(LimbVertMoving, -100, +100, (VerticalJoint * ( -2 ) + 100), 100); // Устанавливаем угол (LimbHorizMoving) для горизонтального сустава конечности (LimbNumber) joint_move_func(LimbNumber, HORIZONTAL_JOINT, LimbHorizMoving); // Устанавливаем угол (LimbVertMoving) для вертикального сустава конечности (LimbNumber) joint_move_func(LimbNumber, VERTICAL_JOINT, LimbVertMoving); } // Функция выполнения походки по одному из возможных вариантов i // Где «LimbMovingType» - номер походки (0-2), «JointPos» - позиция конечности (0-255), «JointHorizMoving» - поворот горизонтальных суставов (-100 +100), «JointVertMoving» - высота вертикального сустава (0-100%) void gait_func(uint8_t LimbMovingType, uint8_t JointPos, int JointHorizMoving, int JointVertMoving){ // Устанавливаем тип походки switch(LimbMovingType){ // Походка номер 0: разворот на месте: // pos = 0 63 127 191 255 case ROTATION_MOVING: // | | | | | limb_step_func(1, 31+JointPos, JointHorizMoving, JointVertMoving); // L | > > > > | > > > > | > > > > | <<< > > | конечность №1 выполняет полный цикл движений (от 255 до 0) быстро возвращаясь в последней тетраде limb_step_func(2, 0-JointPos, JointHorizMoving, JointVertMoving); // R | >>> < < | < < < < | < < < < | < < < < | конечность №2 выполняет полный цикл движений (от 0 до 255) быстро возвращаясь в первой тетраде limb_step_func(3, 95+JointPos, JointHorizMoving, JointVertMoving); // L | > > > > | > > > > | <<< > > | > > > > | конечность №3 выполняет полный цикл движений (от 255 до 0) быстро возвращаясь в предпоследней тетраде limb_step_func(4, 63-JointPos, JointHorizMoving, JointVertMoving); // R | < < < < | >>> < < | < < < < | < < < < | конечность №4 выполняет полный цикл движений (от 0 до 255) быстро возвращаясь во второй тетраде break; // | | | | | // Походка номер 1: движение вперёд или назад: // pos = 0 63 127 191 255 case NORMAL_MOVING: // | | | | | limb_step_func(1, 0+JointPos, JointHorizMoving, JointVertMoving); // L | > > > > | > > > > | > > > > | > > <<< | конечность №1 выполняет полный цикл движений (от 0 до 255) быстро возвращаясь в последней тетраде limb_step_func(2, 127+JointPos, JointHorizMoving, JointVertMoving); // R | > > > > | > > <<< | > > > > | > > > > | конечность №2 выполняет полный цикл движений (от 0 до 255) быстро возвращаясь во второй тетраде limb_step_func(3, 63+JointPos, JointHorizMoving, JointVertMoving); // L | > > > > | > > > > | > > <<< | > > > > | конечность №3 выполняет полный цикл движений (от 0 до 255) быстро возвращаясь в предпоследней тетраде limb_step_func(4, 191+JointPos, JointHorizMoving, JointVertMoving); // R | > > <<< | > > > > | > > > > | > > > > | конечность №4 выполняет полный цикл движений (от 0 до 255) быстро возвращаясь в первой тетраде break; // | | | | | // Походка номер 2: плывёт вперёд или назад: // pos = 0 63 127 191 255 case SMOOTH_MOVING: // | | | | | limb_step_func(1, 0+JointPos, JointHorizMoving, JointVertMoving); // L | > > > > | > > > > | > > > > | > > <<< | конечность №1 выполняет полный цикл движений (от 0 до 255) быстро возвращаясь в последней тетраде limb_step_func(2, 0+JointPos, JointHorizMoving, JointVertMoving); // R | > > > > | > > > > | > > > > | > > <<< | конечность №2 выполняет полный цикл движений (от 0 до 255) быстро возвращаясь в последней тетраде limb_step_func(3, 0+JointPos, JointHorizMoving, JointVertMoving); // L | > > > > | > > > > | > > > > | > > <<< | конечность №3 выполняет полный цикл движений (от 0 до 255) быстро возвращаясь в последней тетраде limb_step_func(4, 0+JointPos, JointHorizMoving, JointVertMoving); // R | > > > > | > > > > | > > > > | > > <<< | конечность №4 выполняет полный цикл движений (от 0 до 255) быстро возвращаясь в последней тетраде break; // | | | | | } }
Значения массива CENTR_ANGLE
должны быть изменены (откалиброваны) на действительные углы сервоприводов в градусах, при которых все суставы робота находятся в центральном положении. Это выполняется с использованием калибровочного скетча, как описано на странице Сборка QUADRUPED. Электроника + Калибровка.
Получение данных с пульта
- Данный блок начинается с оператора
if
в условии которого написаноIR.check(true)
. Это условие верно, если с ИК-пульта приходят пакеты на ИК-приёмник. - Далее следует оператор
if
условием которого являетсяIR.data ==
. Далее указан код кнопки ИК-пульта. Если код совпадает, то выполняется код в теле оператора, код которого совпал с принятым от ИК-пульта. - При выполнении кода в теле оператора
if
так же обновляется значение счётчика времениFlgTime
, который в последствии будет использоваться для ограничения времени на получение пакета (в скетче выше время получения указано ниже в виде(FlgTime + IR_SIGNAL_WAITING_TIME) > millis())
.
В данном коде управление роботом осуществляется через функции:
- joint_move_func - установка одного сустава выбранной конечности в значение от -100 до 100.
- Если указать
joint_move_func(4,1,100)
, то у 4 конечности, вертикальный сустав, поднимется максимально вверх. - Если указать
joint_move_func(4,1,-100)
, то у 4 конечности, горизонтальный сустав, сдвинется максимально влево.
- Если указать
- limb_step_func - установка одной конечности в положение от 0 до 255.
- Если указать
limb_step_func(4,x,0,50)
, где x будет увеличиваться от 0 до 255, то 4 конечность совершит следующие действия: плавный сдвиг внизу назад, резкий подъём, быстрый проход сверху вперёд и резкий спуск, остановившись в той же позиции с которой начинались движения. Что похоже на реальное движение лап при движении вперёд. - Если указать
limb_step_func(4,x,0,50)
, где x будет уменьшаться от 255 до 0, то 4 конечность совершит те же действия, но в обратном порядке. Что похоже на реальное движение лап при движении назад. - Предпоследний аргумент функции можно указывать в пределах от -100 до +100, он будет ограничивать амплитуду движений левых или правых конечностей, что вызовет заворачивание (поворот) влево (-100...0) или вправо (0...+100).
- Последний аргумент функции можно указывать в пределах от 0 до 100, это высота подъёма корпуса в процентах, если указать 0, то QUADRUPED будет «ползти», чем больше значение, тем выше QUADRUPED. Средний подъём корпуса соответствует значению 50.
- Если указать
- gait_func - установка всех конечностей в положение от 0 до 255. Эта функция вызывает предыдущую функцию
limb_step_func
для каждой конечности, указывая их положение в соответствии с алгоритмом походки.- Если указать
limb_step_fun(1,X,0,50)
, где x будет увеличиваться от 0 до 255, то все конечности совершат действия при которых QUADRUPED пройдёт вперёд и прямо на один полный шаг, а его конечности вернутся в ту же позицию с которой этот шаг начинался. - Если указать
limb_step_func(1,X,0,50)
, где x будет уменьшаться от 255 до 0, то все конечности совершат те же действия, но в обратном порядке. Следовательно, QUADRUPED пройдёт тот же шаг но назад. - Если указать
limb_step_func(0,X,0,50)
, где x будет увеличиваться от 0 до 255, то все конечности совершат действия при которых QUADRUPED выполнит разворот вправо на один полный шаг, а его конечности вернутся в ту же позицию с которой этот разворот начинался. - Последний и предпоследний аргументы выполняют те же действия что и аргументы функции
limb_step_func
той же позиции, а именно, выполняют заворот (поворот) и поднятие корпуса. - Вы можете дополнить функцию
gait_func
придумав свои варианты походок.
- Если указать
- free_limp_func - ослабление всех суставов. Функция вызывается без параметров и приводит к отключению сервоприводов. Сервоприводы включатся самостоятельно при вызове любой функции управления суставами или конечностями.
- centr_limb_func - установка всех суставов в центральное положение. Функция вызывается без параметров и устанавливает суставы всех конечностей в положение установленное при калибровке.
Управление:
Управление QUADRUPEDом начинается после того, как на него будет подано питание и все сервоприводы будут выставлены в центральные положения (требуется предварительная калибровка). После этого кнопками пульта со стрелками можно управлять направлением движения робота.
Обсуждение